LookAtTFTask.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2019 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
7 #include <mc_tasks_ros/api.h>
8 
9 #include <mc_tasks/LookAtTask.h>
10 
11 #include <tf2_ros/buffer.h>
12 #include <tf2_ros/transform_listener.h>
13 
14 namespace mc_tasks
15 {
20 {
35  LookAtTFTask(const mc_rbdyn::RobotFrame & frame,
36  const Eigen::Vector3d & frameVector,
37  const std::string & sourceFrame,
38  const std::string & targetFrame,
39  double stiffness = 0.5,
40  double weight = 200);
41 
61  LookAtTFTask(const std::string & bodyName,
62  const Eigen::Vector3d & bodyVector,
63  const std::string & sourceFrame,
64  const std::string & targetFrame,
65  const mc_rbdyn::Robots & robots,
66  unsigned int robotIndex,
67  double stiffness = 0.5,
68  double weight = 200);
69 
71  void update(mc_solver::QPSolver &) override;
72 
73 private:
74  tf2_ros::Buffer tfBuffer;
75  tf2_ros::TransformListener tfListener;
76  std::string sourceFrame;
77  std::string targetFrame;
78 };
79 
80 } // namespace mc_tasks
mc_rbdyn::Robots
Definition: Robots.h:15
MC_TASKS_ROS_DLLAPI
#define MC_TASKS_ROS_DLLAPI
Definition: api.h:47
api.h
mc_solver::QPSolver
Definition: QPSolver.h:85
LookAtTask.h
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_tasks::LookAtTFTask
Control the gaze vector of a body to look towards a world position updated at each iteration from a R...
Definition: LookAtTFTask.h:19
mc_tasks
Definition: StabilizerStandingState.h:11