pr2_point_frame.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <ros/ros.h>
36 
37 #include <vector>
38 #include <boost/scoped_ptr.hpp>
39 #include <boost/thread/condition.hpp>
40 
42 #include <geometry_msgs/PoseStamped.h>
43 #include <geometry_msgs/PointStamped.h>
44 #include <geometry_msgs/Twist.h>
45 
46 #include <kdl/chainfksolver.hpp>
47 #include <kdl/chain.hpp>
48 #include <kdl/chainjnttojacsolver.hpp>
49 #include <kdl/frames.hpp>
50 #include "kdl/chainfksolverpos_recursive.hpp"
52 
53 #include "tf_conversions/tf_kdl.h"
55 #include <tf/message_filter.h>
56 #include <tf/transform_datatypes.h>
57 #include <tf/transform_listener.h>
58 
59 #include <sensor_msgs/JointState.h>
60 #include <std_msgs/Float32MultiArray.h>
61 #include <std_msgs/Int32.h>
62 
63 #include <urdf/model.h>
64 
65 #include <trajectory_msgs/JointTrajectory.h>
66 #include <pr2_controllers_msgs/PointHeadAction.h>
67 #include <pr2_controllers_msgs/QueryTrajectoryState.h>
68 #include <pr2_controllers_msgs/JointTrajectoryControllerState.h>
69 
70 
71 void printVector3(const char * label, tf::Vector3 v)
72 {
73  printf("%s % 7.3f % 7.3f % 7.3f\n", label, v.x(), v.y(), v.z() );
74 
75 }
76 
78 {
79 private:
82 
83  std::string node_name_;
84  std::string action_name_;
85  std::string root_;
86  std::string tip_;
87  std::string pan_link_;
89  std::string pointing_frame_;
91  std::vector< std::string> joint_names_;
92 
99 
102  GoalHandle active_goal_;
104  std::string pan_parent_;
106 
107  geometry_msgs::PointStamped target_;
111 
112  boost::scoped_ptr<KDL::ChainFkSolverPos> pose_solver_;
113  boost::scoped_ptr<KDL::ChainJntToJacSolver> jac_solver_;
114 
117 
118 public:
119 
121  node_name_(ros::this_node::getName())
122  , action_name_("point_head_action")
123  , nh_(node)
124  , pnh_("~")
125  , action_server_(nh_, action_name_.c_str(),
126  boost::bind(&ControlHead::goalCB, this, _1),
127  boost::bind(&ControlHead::cancelCB, this, _1), false)
128  , has_active_goal_(false)
129  {
130  pnh_.param("pan_link", pan_link_, std::string("head_pan_link"));
131  pnh_.param("default_pointing_frame", default_pointing_frame_, std::string("head_tilt_link"));
132  pnh_.param("success_angle_threshold", success_angle_threshold_, 0.1);
133 
134  if(pan_link_[0] == '/') pan_link_.erase(0, 1);
135  if(default_pointing_frame_[0] == '/') default_pointing_frame_.erase(0, 1);
136 
137  // Connects to the controller
138  pub_controller_command_ =
139  nh_.advertise<trajectory_msgs::JointTrajectory>("command", 2);
140  sub_controller_state_ =
141  nh_.subscribe("state", 1, &ControlHead::controllerStateCB, this);
142  cli_query_traj_ =
143  nh_.serviceClient<pr2_controllers_msgs::QueryTrajectoryState>("/head_traj_controller/query_state");
144 
145  // Should only ever happen on first call... move to constructor?
146  if(tree_.getNrOfJoints() == 0)
147  {
148  std::string robot_desc_string;
149  nh_.param("/robot_description", robot_desc_string, std::string());
150  ROS_DEBUG("Reading tree from robot_description...");
151  if (!kdl_parser::treeFromString(robot_desc_string, tree_)){
152  ROS_ERROR("Failed to construct kdl tree");
153  exit(-1);
154  }
155  if (!urdf_model_.initString(robot_desc_string)){
156  ROS_ERROR("Failed to parse urdf string for urdf::Model.");
157  exit(-2);
158  }
159  }
160 
161  ROS_DEBUG("Tree has %d joints and %d segments.", tree_.getNrOfJoints(), tree_.getNrOfSegments());
162 
163  action_server_.start();
164 
165  watchdog_timer_ = nh_.createTimer(ros::Duration(1.0), &ControlHead::watchdog, this);
166  }
167 
168  void goalCB(GoalHandle gh)
169  {
170  // Before we do anything, we need to know that name of the pan_link's parent, which we will treat as the root.
171  if (root_.empty())
172  {
173  for (int i = 0; i < 10; ++i)
174  {
175  try {
176  tfl_.getParent(pan_link_, ros::Time(), root_);
177  break;
178  }
179  catch (const tf::TransformException &ex) {}
180  ros::Duration(0.5).sleep();
181  }
182  if (root_.empty())
183  {
184  ROS_ERROR("Could not get parent of %s in the TF tree", pan_link_.c_str());
185  gh.setRejected();
186  return;
187  }
188  }
189  if(root_[0] == '/') root_.erase(0, 1);
190 
191  ROS_DEBUG("Got point head goal!");
192 
193  // Process pointing frame and axis
194  const geometry_msgs::PointStamped &target = gh.getGoal()->target;
195  pointing_frame_ = gh.getGoal()->pointing_frame;
196  if(pointing_frame_.length() == 0)
197  {
198  ROS_WARN("Pointing frame not specified, using %s [1, 0, 0] by default.", default_pointing_frame_.c_str());
199  pointing_frame_ = default_pointing_frame_;
200  pointing_axis_ = tf::Vector3(1.0, 0.0, 0.0);
201  }
202  else
203  {
204  if(pointing_frame_[0] == '/') pointing_frame_.erase(0, 1);
205  bool ret1 = false;
206  try
207  {
208  std::string error_msg;
209  ret1 = tfl_.waitForTransform(pan_link_, pointing_frame_, target.header.stamp,
210  ros::Duration(5.0), ros::Duration(0.01), &error_msg);
211 
212  tf::vector3MsgToTF(gh.getGoal()->pointing_axis, pointing_axis_);
213  if(pointing_axis_.length() < 0.1)
214  {
215  size_t found = pointing_frame_.find("optical_frame");
216  if (found != std::string::npos)
217  {
218  ROS_WARN("Pointing axis appears to be zero-length. Using [0, 0, 1] as default for an optical frame.");
219  pointing_axis_ = tf::Vector3(0, 0, 1);
220  }
221  else
222  {
223  ROS_WARN("Pointing axis appears to be zero-length. Using [1, 0, 0] as default for a non-optical frame.");
224  pointing_axis_ = tf::Vector3(1, 0, 0);
225  }
226  }
227  else
228  {
229  pointing_axis_.normalize();
230  }
231  }
232  catch(const tf::TransformException &ex)
233  {
234  ROS_ERROR("Transform failure (%d): %s", ret1, ex.what());
235  gh.setRejected();
236  return;
237  }
238  }
239 
240  //Put the target point in the root frame (usually torso_lift_link).
241  bool ret1 = false;
242  try
243  {
244  std::string error_msg;
245  ret1 = tfl_.waitForTransform(root_.c_str(), target.header.frame_id, target.header.stamp,
246  ros::Duration(5.0), ros::Duration(0.01), &error_msg);
247 
248  geometry_msgs::PointStamped target_in_root_msg;
249  tfl_.transformPoint(root_.c_str(), target, target_in_root_msg );
250  tf::pointMsgToTF(target_in_root_msg.point, target_in_root_);
251  }
252  catch(const tf::TransformException &ex)
253  {
254  ROS_ERROR("Transform failure (%d): %s", ret1, ex.what());
255  gh.setRejected();
256  return;
257  }
258 
259  if( tip_.compare(pointing_frame_) != 0 )
260  {
261  bool success = tree_.getChain(root_.c_str(), pointing_frame_.c_str(), chain_);
262  if( !success )
263  {
264  ROS_ERROR("Couldn't create chain from %s to %s.", root_.c_str(), pointing_frame_.c_str());
265  gh.setRejected();
266  return;
267  }
268  tip_ = pointing_frame_;
269 
270  pose_solver_.reset(new KDL::ChainFkSolverPos_recursive(chain_));
271  jac_solver_.reset(new KDL::ChainJntToJacSolver(chain_));
272  joint_names_.resize(chain_.getNrOfJoints());
273  }
274 
275  unsigned int joints = chain_.getNrOfJoints();
276 
277 // int segments = chain_.getNrOfSegments();
278 // ROS_INFO("Parsed urdf from %s to %s and found %d joints and %d segments.", root_.c_str(), pointing_frame_.c_str(), joints, segments);
279 // for(int i = 0; i < segments; i++)
280 // {
281 // KDL::Segment segment = chain_.getSegment(i);
282 // ROS_INFO("Segment %d, %s: joint %s type %s",
283 // i, segment.getName().c_str(), segment.getJoint().getName().c_str(), segment.getJoint().getTypeName().c_str() );
284 // }
285 
286  KDL::JntArray jnt_pos(joints), jnt_eff(joints);
287  KDL::Jacobian jacobian(joints);
288 
289  pr2_controllers_msgs::QueryTrajectoryState traj_state;
290  traj_state.request.time = ros::Time::now() + ros::Duration(0.01);
291  if (!cli_query_traj_.call(traj_state))
292  {
293  ROS_ERROR("Service call to query controller trajectory failed.");
294  gh.setRejected();
295  return;
296  }
297  if(traj_state.response.name.size() != joints)
298  {
299  ROS_ERROR("Number of joints mismatch: urdf chain vs. trajectory controller state.");
300  gh.setRejected();
301  return;
302  }
303  std::vector<urdf::JointLimits> limits_(joints);
304 
305  // Get initial joint positions and joint limits.
306  for(unsigned int i = 0; i < joints; i++)
307  {
308  joint_names_[i] = traj_state.response.name[i];
309  limits_[i] = *(urdf_model_.joints_[joint_names_[i].c_str()]->limits);
310  ROS_DEBUG("Joint %d %s: %f, limits: %f %f", i, traj_state.response.name[i].c_str(), traj_state.response.position[i], limits_[i].lower, limits_[i].upper);
311  //jnt_pos(i) = traj_state.response.position[i];
312  jnt_pos(i) = 0;
313  }
314 
315  int count = 0;
316  int limit_flips = 0;
317  float correction_angle = 2*M_PI;
318  float correction_delta = 2*M_PI;
319  while( ros::ok() && fabs(correction_delta) > 0.001)
320  {
321  //get the pose and jacobian for the current joint positions
322  KDL::Frame pose;
323  pose_solver_->JntToCart(jnt_pos, pose);
324  jac_solver_->JntToJac(jnt_pos, jacobian);
325 
326  tf::Transform frame_in_root;
327  tf::poseKDLToTF(pose, frame_in_root);
328 
329  tf::Vector3 axis_in_frame = pointing_axis_.normalized();
330  tf::Vector3 target_from_frame = (target_in_root_ - frame_in_root.getOrigin()).normalized();
331  tf::Vector3 current_in_frame = frame_in_root.getBasis().inverse()*target_from_frame;
332  float prev_correction = correction_angle;
333  correction_angle = current_in_frame.angle(axis_in_frame);
334  correction_delta = correction_angle - prev_correction;
335  ROS_DEBUG("At step %d, joint poses are %.4f and %.4f, angle error is %f", count, jnt_pos(0), jnt_pos(1), correction_angle);
336  if(correction_angle < 0.5*success_angle_threshold_) break;
337  tf::Vector3 correction_axis = frame_in_root.getBasis()*(axis_in_frame.cross(current_in_frame).normalized());
338  //printVector3("correction_axis in root:", correction_axis);
339  tf::Transform correction_tf(tf::Quaternion(correction_axis, 0.5*correction_angle), tf::Vector3(0,0,0));
340  KDL::Frame correction_kdl;
341  tf::transformTFToKDL(correction_tf, correction_kdl);
342 
343  // We apply a "wrench" proportional to the desired correction
344  KDL::Frame identity_kdl;
345  KDL::Twist twist = diff(correction_kdl, identity_kdl);
346  KDL::Wrench wrench_desi;
347  for (unsigned int i=0; i<6; i++)
348  wrench_desi(i) = -1.0*twist(i);
349 
350  // Converts the "wrench" into "joint corrections" with a jacbobian-transpose
351  for (unsigned int i = 0; i < joints; i++)
352  {
353  jnt_eff(i) = 0;
354  for (unsigned int j=0; j<6; j++)
355  jnt_eff(i) += (jacobian(j,i) * wrench_desi(j));
356  jnt_pos(i) += jnt_eff(i);
357  }
358 
359  // account for pan_link joint limit in back.
360  if(jnt_pos(0) < limits_[0].lower && limit_flips++ == 0){ jnt_pos(0) += 1.5*M_PI; }
361  if(jnt_pos(0) > limits_[0].upper && limit_flips++ == 0){ jnt_pos(0) -= 1.5*M_PI; }
362 
363  jnt_pos(1) = std::max(limits_[1].lower, jnt_pos(1));
364  jnt_pos(1) = std::min(limits_[1].upper, jnt_pos(1));
365 
366  count++;
367 
368  if(limit_flips > 1){
369  ROS_ERROR("Goal is out of joint limits, trying to point there anyway... \n");
370  break;
371  }
372  }
373  ROS_DEBUG("Iterative solver took %d steps", count);
374 
375  std::vector<double> q_goal(joints);
376 
377  for(unsigned int i = 0; i < joints; i++)
378  {
379  jnt_pos(i) = std::max(limits_[i].lower, jnt_pos(i));
380  jnt_pos(i) = std::min(limits_[i].upper, jnt_pos(i));
381  q_goal[i] = jnt_pos(i);
382  ROS_DEBUG("Joint %d %s: %f", i, joint_names_[i].c_str(), jnt_pos(i));
383  }
384 
385  if (has_active_goal_)
386  {
387  active_goal_.setCanceled();
388  has_active_goal_ = false;
389  }
390 
391  gh.setAccepted();
392  active_goal_ = gh;
393  has_active_goal_ = true;
394 
395 
396  // Computes the duration of the movement.
397  ros::Duration min_duration(0.01);
398 
399  if (gh.getGoal()->min_duration > min_duration)
400  min_duration = gh.getGoal()->min_duration;
401 
402  // Determines if we need to increase the duration of the movement in order to enforce a maximum velocity.
403  if (gh.getGoal()->max_velocity > 0)
404  {
405  // Very approximate velocity limiting.
406  double dist = sqrt(pow(q_goal[0] - traj_state.response.position[0], 2) +
407  pow(q_goal[1] - traj_state.response.position[1], 2));
408  ros::Duration limit_from_velocity(dist / gh.getGoal()->max_velocity);
409  if (limit_from_velocity > min_duration)
410  min_duration = limit_from_velocity;
411  }
412 
413 
414  // Computes the command to send to the trajectory controller.
415  trajectory_msgs::JointTrajectory traj;
416  traj.header.stamp = traj_state.request.time;
417 
418  traj.joint_names.push_back(traj_state.response.name[0]);
419  traj.joint_names.push_back(traj_state.response.name[1]);
420 
421  traj.points.resize(2);
422  traj.points[0].positions = traj_state.response.position;
423  traj.points[0].velocities = traj_state.response.velocity;
424  traj.points[0].time_from_start = ros::Duration(0.0);
425  traj.points[1].positions = q_goal;
426  traj.points[1].velocities.push_back(0);
427  traj.points[1].velocities.push_back(0);
428  traj.points[1].time_from_start = ros::Duration(min_duration);
429 
430  pub_controller_command_.publish(traj);
431  }
432 
433 
434  void watchdog(const ros::TimerEvent &e)
435  {
436  ros::Time now = ros::Time::now();
437 
438  // Aborts the active goal if the controller does not appear to be active.
439  if (has_active_goal_)
440  {
441  bool should_abort = false;
443  {
444  should_abort = true;
445  ROS_WARN("Aborting goal because we have never heard a controller state message.");
446  }
447  else if ((now - last_controller_state_->header.stamp) > ros::Duration(5.0))
448  {
449  should_abort = true;
450  ROS_WARN("Aborting goal because we haven't heard from the controller in %.3lf seconds",
451  (now - last_controller_state_->header.stamp).toSec());
452  }
453 
454  if (should_abort)
455  {
456  // Stops the controller.
457  trajectory_msgs::JointTrajectory empty;
458  empty.joint_names = joint_names_;
459  pub_controller_command_.publish(empty);
460 
461  // Marks the current goal as aborted.
462  active_goal_.setAborted();
463  has_active_goal_ = false;
464  }
465  }
466  }
467 
468 
469  void cancelCB(GoalHandle gh)
470  {
471  if (active_goal_ == gh)
472  {
473  // Stops the controller.
474  trajectory_msgs::JointTrajectory empty;
475  empty.joint_names = joint_names_;
476  pub_controller_command_.publish(empty);
477 
478  // Marks the current goal as canceled.
479  active_goal_.setCanceled();
480  has_active_goal_ = false;
481  }
482  }
483 
484  pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_;
485  void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
486  {
487  last_controller_state_ = msg;
488  ros::Time now = ros::Time::now();
489 
490  if (!has_active_goal_)
491  return;
492 
494  try
495  {
496  KDL::JntArray jnt_pos(msg->joint_names.size());
497  for(unsigned int i = 0; i < msg->joint_names.size(); i++)
498  jnt_pos(i) = msg->actual.positions[i];
499 
500  KDL::Frame pose;
501  pose_solver_->JntToCart(jnt_pos, pose);
502 
503  tf::Transform frame_in_root;
504  tf::poseKDLToTF(pose, frame_in_root);
505 
506  tf::Vector3 axis_in_frame = pointing_axis_.normalized();
507  tf::Vector3 target_from_frame = target_in_root_ - frame_in_root.getOrigin();
508 
509  target_from_frame.normalize();
510  tf::Vector3 current_in_frame = frame_in_root.getBasis().inverse()*target_from_frame;
511 
512  pr2_controllers_msgs::PointHeadFeedback feedback;
513  feedback.pointing_angle_error = current_in_frame.angle(axis_in_frame);
514  active_goal_.publishFeedback(feedback);
515 
516  if (feedback.pointing_angle_error < success_angle_threshold_)
517  {
518  active_goal_.setSucceeded();
519  has_active_goal_ = false;
520  }
521  }
522  catch(const tf::TransformException &ex)
523  {
524  ROS_ERROR("Could not transform: %s", ex.what());
525  }
526  }
527 
528 
529 };
530 
531 int main(int argc, char** argv)
532 {
533  ros::init(argc, argv, "point_head_action");
534  ros::NodeHandle node;
535  ControlHead ch(node);
536  ros::spin();
537  return 0;
538 }
539 
ros::NodeHandle pnh_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::vector< std::string > joint_names_
std::string action_name_
std::string root_
std::string default_pointing_frame_
static void pointMsgToTF(const geometry_msgs::Point &msg_v, Point &bt_v)
void publish(const boost::shared_ptr< M > &message) const
URDF_EXPORT bool initString(const std::string &xmlstring)
ServerGoalHandle< pr2_controllers_msgs::PointHeadAction > GoalHandle
std::string pointing_frame_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
tf::Stamped< tf::Point > target_in_pan_
bool getParent(const std::string &frame_id, ros::Time time, std::string &parent) const
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
urdf::Model urdf_model_
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
bool call(MReq &req, MRes &res)
std::string getName(void *handle)
void printVector3(const char *label, tf::Vector3 v)
double success_angle_threshold_
void transformPoint(const std::string &target_frame, const geometry_msgs::PointStamped &stamped_in, geometry_msgs::PointStamped &stamped_out) const
tf::Vector3 pointing_axis_
Matrix3x3 inverse() const
TFSIMD_FORCE_INLINE tfScalar angle(const Vector3 &v) const
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_
#define ROS_WARN(...)
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
void controllerStateCB(const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
ROSCPP_DECL void spin(Spinner &spinner)
ros::Subscriber command_sub_
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
ros::Publisher pub_controller_command_
boost::scoped_ptr< KDL::ChainJntToJacSolver > jac_solver_
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE Vector3 normalized() const
actionlib::ActionServer< pr2_controllers_msgs::PointHeadAction > PHAS
ros::NodeHandle nh_
static void vector3MsgToTF(const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v)
TFSIMD_FORCE_INLINE const tfScalar & z() const
void poseKDLToTF(const KDL::Frame &k, tf::Pose &t)
void transformTFToKDL(const tf::Transform &t, KDL::Frame &k)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string pan_parent_
TFSIMD_FORCE_INLINE Vector3 normalized() const
ROSCPP_DECL bool ok()
TFSIMD_FORCE_INLINE const tfScalar & y() const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ControlHead(const ros::NodeHandle &node)
void goalCB(GoalHandle gh)
void watchdog(const ros::TimerEvent &e)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getNrOfJoints() const
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
KDL_PARSER_PUBLIC bool treeFromString(const std::string &xml, KDL::Tree &tree)
std::string tip_
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
tf::Point target_in_root_
TFSIMD_FORCE_INLINE Vector3 & normalize()
int main(int argc, char **argv)
GoalHandle active_goal_
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
tf::TransformListener tfl_
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
geometry_msgs::PointStamped target_
unsigned int getNrOfSegments() const
void cancelCB(GoalHandle gh)
std::string pan_link_
static Time now()
ros::Subscriber sub_controller_state_
ros::Timer watchdog_timer_
PHAS::GoalHandle GoalHandle
KDL::Chain chain_
unsigned int getNrOfJoints() const
#define ROS_ERROR(...)
std::string node_name_
ros::ServiceClient cli_query_traj_
boost::scoped_ptr< KDL::ChainFkSolverPos > pose_solver_
TFSIMD_FORCE_INLINE tfScalar length() const
#define ROS_DEBUG(...)


pr2_head_action
Author(s): Stuart Glaser
autogenerated on Wed Jun 5 2019 19:34:00