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 {
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
#define MC_TASKS_DLLAPI
Definition: api.h:50
Definition: StabilizerStandingState.h:12
Definition: RobotFrame.h:22
Definition: Robots.h:16
Simplify access to values hold within a JSON file.
Definition: Configuration.h:166
Logs controller data to disk.
Definition: Logger.h:30
Definition: StateBuilder.h:28
Definition: QPSolver.h:86
Orient a "gaze" vector defined on a body to look towards a world position. This task is a convenience...
Definition: LookAtTask.h:15
LookAtTask(const std::string &bodyName, const Eigen::Vector3d &bodyVector, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=500)
Constructor with default target initialization.
void target(const Eigen::Vector3d &pos)
Look towards the target frame position.
LookAtTask(const std::string &bodyName, const Eigen::Vector3d &bodyVector, const Eigen::Vector3d &targetPos, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=2.0, double weight=500)
Constructor with user-specified target initialization.
void reset() override
Reset the task.
void load(mc_solver::QPSolver &solver, const mc_rtc::Configuration &config) override
Load parameters from a Configuration object.
Eigen::Vector3d target() const
Gets the target frame position See targetVector() to obtain the gaze vector.
LookAtTask(const mc_rbdyn::RobotFrame &frame, const Eigen::Vector3d &frameVector, double stiffness=2.0, double weight=500.0)
Constructor with a frame.
Control the orientation of a vector attached to a frame.
Definition: VectorOrientationTask.h:14