GazeTask.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2022 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
8 
9 namespace mc_tasks
10 {
11 
14 {
15 public:
26  GazeTask(const mc_rbdyn::RobotFrame & frame,
27  double stiffness = 2.0,
28  double weight = 500.0,
29  const Eigen::Vector3d & error = Eigen::Vector3d::UnitZ());
30 
49  GazeTask(const std::string & bodyName,
50  const Eigen::Vector2d & point2d,
51  double depthEstimate,
52  const sva::PTransformd & X_b_gaze,
53  const mc_rbdyn::Robots & robots,
54  unsigned int robotIndex,
55  double stiffness = 2.0,
56  double weight = 500);
57 
79  GazeTask(const std::string & bodyName,
80  const Eigen::Vector3d & point3d,
81  const sva::PTransformd & X_b_gaze,
82  const mc_rbdyn::Robots & robots,
83  unsigned int robotIndex,
84  double stiffness = 2.0,
85  double weight = 500);
86 
91  void reset() override;
92 
100  void error(const Eigen::Vector2d & point2d, const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero());
101 
109  void error(const Eigen::Vector3d & point3d, const Eigen::Vector2d & point2d_ref = Eigen::Vector2d::Zero());
110 };
111 
112 } // namespace mc_tasks
mc_rbdyn::Robots
Definition: Robots.h:15
MC_TASKS_DLLAPI
#define MC_TASKS_DLLAPI
Definition: api.h:50
mc_rbdyn::RobotFrame
Definition: RobotFrame.h:21
mc_tasks::GazeTask
Control the Gaze of a body.
Definition: GazeTask.h:13
mc_rtc::log::error
void error(Args &&... args)
Definition: logging.h:63
mc_tasks
Definition: StabilizerStandingState.h:11
TrajectoryTaskGeneric.h
mc_tasks::TrajectoryTaskGeneric
Generic wrapper for a trajectory dynamic over an error function.
Definition: TrajectoryTaskGeneric.h:26