11 #include <tf2_ros/buffer.h>
12 #include <tf2_ros/transform_listener.h>
36 const Eigen::Vector3d & frameVector,
37 const std::string & sourceFrame,
38 const std::string & targetFrame,
39 double stiffness = 0.5,
62 const Eigen::Vector3d & bodyVector,
63 const std::string & sourceFrame,
64 const std::string & targetFrame,
66 unsigned int robotIndex,
67 double stiffness = 0.5,
74 tf2_ros::Buffer tfBuffer;
75 tf2_ros::TransformListener tfListener;
76 std::string sourceFrame;
77 std::string targetFrame;
Definition: StabilizerStandingState.h:12
#define MC_TASKS_ROS_DLLAPI
Definition: api.h:47
Definition: RobotFrame.h:22
Definition: QPSolver.h:86
Control the gaze vector of a body to look towards a world position updated at each iteration from a R...
Definition: LookAtTFTask.h:20
void update(mc_solver::QPSolver &) override
Update the gaze target from TF position.
LookAtTFTask(const mc_rbdyn::RobotFrame &frame, const Eigen::Vector3d &frameVector, const std::string &sourceFrame, const std::string &targetFrame, double stiffness=0.5, double weight=200)
Constructor.
LookAtTFTask(const std::string &bodyName, const Eigen::Vector3d &bodyVector, const std::string &sourceFrame, const std::string &targetFrame, const mc_rbdyn::Robots &robots, unsigned int robotIndex, double stiffness=0.5, double weight=200)
Constructor.
Orient a "gaze" vector defined on a body to look towards a world position. This task is a convenience...
Definition: LookAtTask.h:15