LookAtTask.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2022 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
7 
8 namespace mc_tasks
9 {
10 
15 {
26  LookAtTask(const mc_rbdyn::RobotFrame & frame,
27  const Eigen::Vector3d & frameVector,
28  double stiffness = 2.0,
29  double weight = 500.0);
30 
49  LookAtTask(const std::string & bodyName,
50  const Eigen::Vector3d & bodyVector,
51  const Eigen::Vector3d & targetPos,
52  const mc_rbdyn::Robots & robots,
53  unsigned int robotIndex,
54  double stiffness = 2.0,
55  double weight = 500);
56 
58  LookAtTask(const std::string & bodyName,
59  const Eigen::Vector3d & bodyVector,
60  const mc_rbdyn::Robots & robots,
61  unsigned int robotIndex,
62  double stiffness = 2.0,
63  double weight = 500);
64 
66  void reset() override;
67 
73  void target(const Eigen::Vector3d & pos);
80  Eigen::Vector3d target() const;
81 
82  void load(mc_solver::QPSolver & solver, const mc_rtc::Configuration & config) override;
83 
84 private:
85  void addToLogger(mc_rtc::Logger & logger) override;
86  void addToGUI(mc_rtc::gui::StateBuilder & gui) override;
87 
88 private:
90  Eigen::Vector3d target_pos_;
91 };
92 
93 } // namespace mc_tasks
mc_rtc::Configuration
Simplify access to values hold within a JSON file.
Definition: Configuration.h:165
mc_rbdyn::Robots
Definition: Robots.h:15
MC_TASKS_DLLAPI
#define MC_TASKS_DLLAPI
Definition: api.h:50
mc_solver::QPSolver
Definition: QPSolver.h:85
mc_rtc::Logger
Logs controller data to disk.
Definition: Logger.h:29
mc_rbdyn::RobotFrame
Definition: RobotFrame.h:21
mc_tasks::LookAtTask
Orient a "gaze" vector defined on a body to look towards a world position. This task is a convenience...
Definition: LookAtTask.h:14
mc_rtc::gui::StateBuilder
Definition: StateBuilder.h:27
mc_tasks::VectorOrientationTask
Control the orientation of a vector attached to a frame.
Definition: VectorOrientationTask.h:13
VectorOrientationTask.h
mc_tasks
Definition: StabilizerStandingState.h:11