cob_twist_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <string>
19 #include <vector>
20 #include <limits>
21 #include <ros/ros.h>
22 
24 
26 #include <tf/transform_datatypes.h>
27 #include <visualization_msgs/Marker.h>
28 #include <visualization_msgs/MarkerArray.h>
29 #include <cob_srvs/SetString.h>
30 
31 #include <Eigen/Dense>
32 
34 {
35  ros::NodeHandle nh_twist("twist_controller");
36 
37  // JointNames
38  if (!nh_.getParam("joint_names", twist_controller_params_.joints))
39  {
40  ROS_ERROR("Parameter 'joint_names' not set");
41  return false;
42  }
43 
45 
46  // Chain
47  if (!nh_.getParam("chain_base_link", twist_controller_params_.chain_base_link))
48  {
49  ROS_ERROR("Parameter 'chain_base_link' not set");
50  return false;
51  }
52 
53  if (!nh_.getParam("chain_tip_link", twist_controller_params_.chain_tip_link))
54  {
55  ROS_ERROR("Parameter 'chain_tip_link' not set");
56  return false;
57  }
58 
59  // links of the chain to be considered for collision avoidance
60  if (!nh_twist.getParam("collision_check_links", twist_controller_params_.collision_check_links))
61  {
62  ROS_WARN_STREAM("Parameter 'collision_check_links' not set. Collision Avoidance constraint will not do anything.");
64  }
65 
67  KDL::Tree my_tree;
68  if (!kdl_parser::treeFromParam("/robot_description", my_tree))
69  {
70  ROS_ERROR("Failed to construct kdl tree");
71  return false;
72  }
73 
75  if (chain_.getNrOfJoints() == 0)
76  {
77  ROS_ERROR("Failed to initialize kinematic chain");
78  return false;
79  }
80 
82  urdf::Model model;
83  if (!model.initParam("/robot_description"))
84  {
85  ROS_ERROR("Failed to parse urdf file for JointLimits");
86  return false;
87  }
88 
89  for (uint16_t i = 0; i < twist_controller_params_.dof; i++)
90  {
91  if (model.getJoint(twist_controller_params_.joints[i])->type == urdf::Joint::CONTINUOUS)
92  {
93  twist_controller_params_.limiter_params.limits_min.push_back(-std::numeric_limits<double>::max());
94  twist_controller_params_.limiter_params.limits_max.push_back(std::numeric_limits<double>::max());
95  }
96  else
97  {
98  twist_controller_params_.limiter_params.limits_min.push_back(model.getJoint(twist_controller_params_.joints[i])->limits->lower);
99  twist_controller_params_.limiter_params.limits_max.push_back(model.getJoint(twist_controller_params_.joints[i])->limits->upper);
100  }
101  twist_controller_params_.limiter_params.limits_vel.push_back(model.getJoint(twist_controller_params_.joints[i])->limits->velocity);
102  }
103 
104  // Currently not supported yet
106  {
107  // ROS_ERROR("Parameter 'limits_acc' not set or dimensions do not match! Not limiting acceleration!");
108  for (uint16_t i = 0; i < twist_controller_params_.dof; i++)
109  {
110  twist_controller_params_.limiter_params.limits_acc.push_back(std::numeric_limits<double>::max());
111  }
112  }
113 
114  // Configure Lookat Extenstion (Offset and Axis) --- not dynamic-reconfigurable
115  if (nh_twist.hasParam("lookat_axis_type"))
116  {
117  int lookat_axis_type;
118  nh_twist.getParam("lookat_axis_type", lookat_axis_type);
120  }
121  if (nh_twist.hasParam("lookat_pointing_frame"))
122  {
123  nh_twist.getParam("lookat_pointing_frame", twist_controller_params_.lookat_pointing_frame);
124  }
125  else
126  {
127  if (nh_twist.hasParam("lookat_offset"))
128  {
129  if (nh_twist.hasParam("lookat_offset/translation"))
130  {
131  twist_controller_params_.lookat_offset.translation_x = nh_twist.param("lookat_offset/translation/x", 0.0);
132  twist_controller_params_.lookat_offset.translation_y = nh_twist.param("lookat_offset/translation/y", 0.0);
133  twist_controller_params_.lookat_offset.translation_z = nh_twist.param("lookat_offset/translation/z", 0.0);
134  }
135  if (nh_twist.hasParam("lookat_offset/rotation"))
136  {
137  twist_controller_params_.lookat_offset.rotation_x = nh_twist.param("lookat_offset/rotation/x", 0.0);
138  twist_controller_params_.lookat_offset.rotation_y = nh_twist.param("lookat_offset/rotation/y", 0.0);
139  twist_controller_params_.lookat_offset.rotation_z = nh_twist.param("lookat_offset/rotation/z", 0.0);
140  twist_controller_params_.lookat_offset.rotation_w = nh_twist.param("lookat_offset/rotation/w", 1.0);
141  }
142  }
143  }
144 
145  // Configure Controller Interface
146  if (!nh_twist.getParam("controller_interface", twist_controller_params_.controller_interface))
147  {
148  ROS_ERROR("Parameter 'controller_interface' not set");
149  return false;
150  }
151  nh_twist.param<double>("integrator_smoothing", twist_controller_params_.integrator_smoothing, 0.2);
152  try
153  {
154  interface_loader_.reset(new pluginlib::ClassLoader<cob_twist_controller::ControllerInterfaceBase>("cob_twist_controller", "cob_twist_controller::ControllerInterfaceBase"));
156  this->controller_interface_->initialize(this->nh_, this->twist_controller_params_);
157  }
159  {
160  ROS_ERROR("The controller_interface plugin failed to load. Error: %s", ex.what());
161  return false;
162  }
163 
165  for (uint16_t i = 0; i < chain_.getNrOfSegments(); ++i)
166  {
168  }
169  register_link_client_ = nh_.serviceClient<cob_srvs::SetString>("obstacle_distance/registerLinkOfInterest");
172 
176 
178  reconfigure_server_.reset(new dynamic_reconfigure::Server<cob_twist_controller::TwistControllerConfig>(reconfig_mutex_, nh_twist));
179  reconfigure_server_->setCallback(boost::bind(&CobTwistController::reconfigureCallback, this, _1, _2));
180 
186 
188  ros::Duration(1.0).sleep();
189 
193  twist_sub_ = nh_twist.subscribe("command_twist", 1, &CobTwistController::twistCallback, this);
194  twist_stamped_sub_ = nh_twist.subscribe("command_twist_stamped", 1, &CobTwistController::twistStampedCallback, this);
195 
196  odometry_sub_ = nh_.subscribe("base/odometry", 1, &CobTwistController::odometryCallback, this);
197 
199  twist_direction_pub_ = nh_.advertise<visualization_msgs::MarkerArray>("twist_direction", 1);
200 
201  ROS_INFO_STREAM(nh_.getNamespace() << "/twist_controller...initialized!");
202  return true;
203 }
204 
206 {
208  "No collision_check_links set for this chain. Nothing will be registered. Ensure parameters are set correctly.");
209 
210  for (std::vector<std::string>::const_iterator it = twist_controller_params_.collision_check_links.begin();
212  it++)
213  {
214  ROS_INFO_STREAM("Trying to register for " << *it);
215  cob_srvs::SetString r;
216  r.request.data = *it;
218  {
219  ROS_INFO_STREAM("Called registration service with success: " << int(r.response.success) << ". Got message: " << r.response.message);
220  if (!r.response.success)
221  {
222  return false;
223  }
224  }
225  else
226  {
227  ROS_WARN_STREAM("Failed to call registration service for namespace: " << nh_.getNamespace());
228  return false;
229  }
230  }
231 
232  return true;
233 }
234 
235 void CobTwistController::reconfigureCallback(cob_twist_controller::TwistControllerConfig& config, uint32_t level)
236 {
238  this->checkSolverAndConstraints(config);
239 
241 
242  if (!p_inv_diff_kin_solver_->resetAll(this->twist_controller_params_))
243  {
244  ROS_ERROR_STREAM("ResetAll during DynamicReconfigureCallback failed! Resetting to previous config");
245  twist_controller_params_ = backup;
247  this->twist_controller_params_.to_config(config);
248  }
249 }
250 
251 void CobTwistController::checkSolverAndConstraints(cob_twist_controller::TwistControllerConfig& config)
252 {
253  bool warning = false;
254 
255  DampingMethodTypes damping = static_cast<DampingMethodTypes>(config.damping_method);
257  {
258  //damping method has changed - setting back to proper default values
259  if (damping == CONSTANT)
260  {
261  config.damping_factor = 0.01;
262  }
263  else if (damping == MANIPULABILITY)
264  {
265  config.lambda_max = 0.1;
266  config.w_threshold = 0.005;
267  }
268  else if (damping == LEAST_SINGULAR_VALUE)
269  {
270  config.lambda_max = 0.1;
271  config.w_threshold = 0.005;
272  }
273  else if (damping == SIGMOID)
274  {
275  config.lambda_max = 0.001;
276  config.w_threshold = 0.001;
277  }
278  }
279 
280  SolverTypes solver = static_cast<SolverTypes>(config.solver);
281 
282  if (DEFAULT_SOLVER == solver && (JLA_OFF != static_cast<ConstraintTypesJLA>(config.constraint_jla) || CA_OFF != static_cast<ConstraintTypesCA>(config.constraint_ca)))
283  {
284  ROS_ERROR("The selection of Default solver and a constraint doesn\'t make any sense. Switch settings back ...");
287  config.constraint_jla = static_cast<int>(twist_controller_params_.constraint_jla);
288  config.constraint_ca = static_cast<int>(twist_controller_params_.constraint_ca);
289  warning = true;
290  }
291 
292  if (WLN == solver && CA_OFF != static_cast<ConstraintTypesCA>(config.constraint_ca))
293  {
294  ROS_ERROR("The WLN solution doesn\'t support collision avoidance. Currently WLN is only implemented for Identity and JLA ...");
296  config.constraint_ca = static_cast<int>(twist_controller_params_.constraint_ca);
297  warning = true;
298  }
299 
300  if (GPM == solver && CA_OFF == static_cast<ConstraintTypesCA>(config.constraint_ca) && JLA_OFF == static_cast<ConstraintTypesJLA>(config.constraint_jla))
301  {
302  ROS_ERROR("You have chosen GPM but without constraints! The behaviour without constraints will be the same like for DEFAULT_SOLVER.");
303  warning = true;
304  }
305 
306  if (TASK_2ND_PRIO == solver && (JLA_ON == static_cast<ConstraintTypesJLA>(config.constraint_jla) || CA_OFF == static_cast<ConstraintTypesCA>(config.constraint_ca)))
307  {
308  ROS_ERROR("The projection of a task into the null space of the main EE task is currently only for the CA constraint supported!");
311  config.constraint_jla = static_cast<int>(twist_controller_params_.constraint_jla);
312  config.constraint_ca = static_cast<int>(twist_controller_params_.constraint_ca);
313  warning = true;
314  }
315 
316  if (UNIFIED_JLA_SA == solver && CA_OFF != static_cast<ConstraintTypesCA>(config.constraint_ca))
317  {
318  ROS_ERROR("The Unified JLA and SA solution doesn\'t support collision avoidance. Currently UNIFIED_JLA_SA is only implemented for SA and JLA ...");
320  config.constraint_ca = static_cast<int>(twist_controller_params_.constraint_ca);
321  warning = true;
322  }
323 
324  if (CA_OFF != static_cast<ConstraintTypesCA>(config.constraint_ca))
325  {
327  {
328  ROS_ERROR("ServiceServer 'obstacle_distance/registerLinkOfInterest' does not exist. CA not possible");
330  config.constraint_ca = static_cast<int>(twist_controller_params_.constraint_ca);
331  warning = true;
332  }
333  else if (twist_controller_params_.constraint_ca != static_cast<ConstraintTypesCA>(config.constraint_ca))
334  {
335  ROS_INFO("Collision Avoidance has been activated! Register links!");
336  if (!this->registerCollisionLinks())
337  {
338  ROS_ERROR("Registration of links failed. CA not possible");
340  config.constraint_ca = static_cast<int>(twist_controller_params_.constraint_ca);
341  warning = true;
342  }
343  }
344  }
345 
347  {
348  ROS_ERROR("The limits_tolerance for enforce limits is smaller than DIV/0 threshold. Therefore output limiting is disabled");
349  twist_controller_params_.limiter_params.enforce_pos_limits = config.enforce_pos_limits = false;
350  twist_controller_params_.limiter_params.enforce_vel_limits = config.enforce_vel_limits = false;
351  twist_controller_params_.limiter_params.enforce_acc_limits = config.enforce_acc_limits = false;
352  }
355  {
356  ROS_ERROR("The limits used to limit Cartesian velocities are smaller than DIV/0 threshold. Therefore input limiting is disabled");
357  twist_controller_params_.limiter_params.enforce_input_limits = config.enforce_input_limits = false;
358  }
359 
360  if (!warning)
361  {
362  ROS_INFO("Parameters seem to be ok.");
363  }
364 }
365 
367 void CobTwistController::twistStampedCallback(const geometry_msgs::TwistStamped::ConstPtr& msg)
368 {
369  tf::StampedTransform transform_tf;
370  KDL::Frame frame;
371  KDL::Twist twist, twist_transformed;
372 
373  try
374  {
375  tf_listener_.lookupTransform(twist_controller_params_.chain_base_link, msg->header.frame_id, ros::Time(0), transform_tf);
376  frame.M = KDL::Rotation::Quaternion(transform_tf.getRotation().x(), transform_tf.getRotation().y(), transform_tf.getRotation().z(), transform_tf.getRotation().w());
377  }
378  catch (tf::TransformException& ex)
379  {
380  ROS_ERROR("CobTwistController::twistStampedCallback: \n%s", ex.what());
381  return;
382  }
383 
384  tf::twistMsgToKDL(msg->twist, twist);
385  twist_transformed = frame*twist;
386  solveTwist(twist_transformed);
387 }
388 
390 void CobTwistController::twistCallback(const geometry_msgs::Twist::ConstPtr& msg)
391 {
392  KDL::Twist twist;
393  tf::twistMsgToKDL(*msg, twist);
394  solveTwist(twist);
395 }
396 
399 {
400  ros::Time start, end;
401  start = ros::Time::now();
402 
403  visualizeTwist(twist);
404 
405  KDL::JntArray q_dot_ik(chain_.getNrOfJoints());
406 
408  {
409  twist = twist - twist_odometry_cb_;
410  }
411 
412  int ret_ik = p_inv_diff_kin_solver_->CartToJnt(this->joint_states_,
413  twist,
414  q_dot_ik);
415 
416  if (0 != ret_ik)
417  {
418  ROS_ERROR("No Vel-IK found!");
419  }
420  else
421  {
422  this->controller_interface_->processResult(q_dot_ik, this->joint_states_.current_q_);
423  }
424 
425  end = ros::Time::now();
426  // ROS_INFO_STREAM("solveTwist took " << (end-start).toSec() << " seconds");
427 }
428 
430 {
433  {
434  tracking_frame = "lookat_focus_frame";
435  }
436 
437  tf::StampedTransform transform_tf;
438  try
439  {
441  }
442  catch (tf::TransformException& ex)
443  {
444  ROS_ERROR("CobTwistController::visualizeTwist: \n%s", ex.what());
445  return;
446  }
447 
448  visualization_msgs::Marker marker_vel;
449  marker_vel.header.frame_id = twist_controller_params_.chain_base_link;
450  marker_vel.header.stamp = ros::Time::now();
451  marker_vel.ns = "twist_vel";
452  marker_vel.id = 0;
453  marker_vel.type = visualization_msgs::Marker::ARROW;
454  marker_vel.action = visualization_msgs::Marker::ADD;
455  marker_vel.lifetime = ros::Duration(0.1);
456  marker_vel.pose.orientation.w = 1.0;
457 
458  marker_vel.scale.x = 0.02;
459  marker_vel.scale.y = 0.02;
460  marker_vel.scale.z = 0.02;
461 
462  marker_vel.color.r = 1.0f;
463  marker_vel.color.g = 1.0f;
464  marker_vel.color.b = 0.0f;
465  marker_vel.color.a = 1.0;
466 
467  marker_vel.points.resize(2);
468  marker_vel.points[0].x = transform_tf.getOrigin().x();
469  marker_vel.points[0].y = transform_tf.getOrigin().y();
470  marker_vel.points[0].z = transform_tf.getOrigin().z();
471  marker_vel.points[1].x = transform_tf.getOrigin().x() + 5.0 * twist.vel.x();
472  marker_vel.points[1].y = transform_tf.getOrigin().y() + 5.0 * twist.vel.y();
473  marker_vel.points[1].z = transform_tf.getOrigin().z() + 5.0 * twist.vel.z();
474 
475  visualization_msgs::Marker marker_rot;
476  marker_rot.header.frame_id = twist_controller_params_.chain_base_link;
477  marker_rot.header.stamp = ros::Time::now();
478  marker_rot.ns = "twist_rot";
479  marker_rot.id = 0;
480  marker_rot.type = visualization_msgs::Marker::CYLINDER;
481  marker_rot.action = visualization_msgs::Marker::ADD;
482  marker_rot.lifetime = ros::Duration(0.1);
483  marker_rot.pose.position.x = transform_tf.getOrigin().x();
484  marker_rot.pose.position.y = transform_tf.getOrigin().y();
485  marker_rot.pose.position.z = transform_tf.getOrigin().z();
486 
487  tf::Quaternion rot;
488  rot.setRPY(twist.rot.x(), twist.rot.y(), twist.rot.z());
489 
491  tf::Vector3 z_axis = tf::Vector3(0, 0, 1);
492  tf::Vector3 t_axis = rot.getAxis();
493  tf::Quaternion temp(0, 0, 0, 1);
494  if (z_axis != t_axis && z_axis != -t_axis)
495  {
496  tf::Vector3 cross = z_axis.cross(t_axis);
497  temp = tf::Quaternion(cross.x(), cross.y(), cross.z(), (std::sqrt(z_axis.length2() * t_axis.length2()) + z_axis.dot(t_axis)));
498  temp = temp.normalized();
499  }
500  tf::quaternionTFToMsg(temp, marker_rot.pose.orientation);
501 
502  marker_rot.scale.x = rot.getAngle();
503  marker_rot.scale.y = rot.getAngle();
504  marker_rot.scale.z = 0.002;
505 
506  marker_rot.color.r = 1.0f;
507  marker_rot.color.g = 1.0f;
508  marker_rot.color.b = 0.0f;
509  marker_rot.color.a = 1.0;
510 
511  visualization_msgs::MarkerArray markers;
512  markers.markers.push_back(marker_vel);
513  markers.markers.push_back(marker_rot);
514 
515  twist_direction_pub_.publish(markers);
516 }
517 
518 void CobTwistController::jointstateCallback(const sensor_msgs::JointState::ConstPtr& msg)
519 {
520  KDL::JntArray q_temp = this->joint_states_.current_q_;
521  KDL::JntArray q_dot_temp = this->joint_states_.current_q_dot_;
522  int count = 0;
523 
524  for (uint16_t j = 0; j < twist_controller_params_.dof; j++)
525  {
526  for (uint16_t i = 0; i < msg->name.size(); i++)
527  {
528  if (strcmp(msg->name[i].c_str(), twist_controller_params_.joints[j].c_str()) == 0)
529  {
530  q_temp(j) = msg->position[i];
531  q_dot_temp(j) = msg->velocity[i];
532  count++;
533  break;
534  }
535  }
536  }
537 
538  if (count == twist_controller_params_.joints.size())
539  {
542  this->joint_states_.current_q_ = q_temp;
543  this->joint_states_.current_q_dot_ = q_dot_temp;
544  }
545 }
546 
547 void CobTwistController::odometryCallback(const nav_msgs::Odometry::ConstPtr& msg)
548 {
549  KDL::Twist twist_odometry_bl, tangential_twist_bl, twist_odometry_transformed_cb;
550  KDL::Frame cb_frame_bl;
551  tf::StampedTransform cb_transform_bl, bl_transform_ct;
552 
553  try
554  {
557 
560 
561  cb_frame_bl.p = KDL::Vector(cb_transform_bl.getOrigin().x(), cb_transform_bl.getOrigin().y(), cb_transform_bl.getOrigin().z());
562  cb_frame_bl.M = KDL::Rotation::Quaternion(cb_transform_bl.getRotation().x(), cb_transform_bl.getRotation().y(), cb_transform_bl.getRotation().z(), cb_transform_bl.getRotation().w());
563  }
564  catch (tf::TransformException& ex)
565  {
566  ROS_ERROR("CobTwistController::odometryCallback: \n%s", ex.what());
567  return;
568  }
569 
570  try
571  {
572  // Calculate tangential twist for angular base movements v = w x r
573  Eigen::Vector3d r(bl_transform_ct.getOrigin().x(), bl_transform_ct.getOrigin().y(), bl_transform_ct.getOrigin().z());
574  Eigen::Vector3d w(0, 0, msg->twist.twist.angular.z);
575  Eigen::Vector3d res = w.cross(r);
576  tangential_twist_bl.vel = KDL::Vector(res(0), res(1), res(2));
577  tangential_twist_bl.rot = KDL::Vector(0, 0, 0);
578  }
579  catch(...)
580  {
581  ROS_ERROR("Error occurred while calculating tangential twist for angular base movements.");
582  return;
583  }
584 
585  tf::twistMsgToKDL(msg->twist.twist, twist_odometry_bl); // Base Twist
586 
587  // transform into chain_base
588  twist_odometry_transformed_cb = cb_frame_bl * (twist_odometry_bl + tangential_twist_bl);
589 
590  twist_odometry_cb_ = twist_odometry_transformed_cb;
591 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::vector< double > limits_min
void distancesToObstaclesCallback(const cob_control_msgs::ObstacleDistances::ConstPtr &msg)
Producer: Fills obstacle distances but only when they are empty.
void reconfigureCallback(cob_twist_controller::TwistControllerConfig &config, uint32_t level)
tfScalar getAngle() const
const Segment & getSegment(unsigned int nr) const
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber jointstate_sub_
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Vector vel
CallbackDataMediator callback_data_mediator_
void jointstateCallback(const sensor_msgs::JointState::ConstPtr &msg)
bool sleep() const
KinematicExtensionTypes kinematic_extension
unsigned int getNrOfSegments() const
bool call(MReq &req, MRes &res)
void twistStampedCallback(const geometry_msgs::TwistStamped::ConstPtr &msg)
Orientation of twist_stamped_msg is with respect to coordinate system given in header.frame_id.
static Rotation Quaternion(double x, double y, double z, double w)
void twistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k)
std::vector< std::string > collision_check_links
double z() const
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
boost::shared_ptr< pluginlib::ClassLoader< cob_twist_controller::ControllerInterfaceBase > > interface_loader_
void odometryCallback(const nav_msgs::Odometry::ConstPtr &msg)
Rotation M
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
std::vector< std::string > frame_names
ros::Subscriber twist_stamped_sub_
TFSIMD_FORCE_INLINE const tfScalar & x() const
const std::string & getName() const
TFSIMD_FORCE_INLINE tfScalar dot(const Vector3 &v) const
TFSIMD_FORCE_INLINE const tfScalar & z() const
std::vector< double > limits_acc
tf::TransformListener tf_listener_
ros::ServiceClient register_link_client_
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
void solveTwist(KDL::Twist twist)
Orientation of twist is with respect to chain_base coordinate system.
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
Vector rot
double y() const
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Subscriber odometry_sub_
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
double x() const
Vector3 getAxis() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
void to_config(cob_twist_controller::TwistControllerConfig &config)
ros::Publisher twist_direction_pub_
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getNrOfJoints() const
URDF_EXPORT bool initParam(const std::string &param)
r
#define ROS_WARN_STREAM(args)
void twistCallback(const geometry_msgs::Twist::ConstPtr &msg)
Orientation of twist_msg is with respect to chain_base coordinate system.
void from_config(cob_twist_controller::TwistControllerConfig config)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
std::vector< double > limits_max
def warning(args, kwargs)
TFSIMD_FORCE_INLINE const tfScalar & w() const
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
KDL_PARSER_PUBLIC bool treeFromParam(const std::string &param, KDL::Tree &tree)
#define ROS_INFO_STREAM(args)
boost::shared_ptr< InverseDifferentialKinematicsSolver > p_inv_diff_kin_solver_
Quaternion getRotation() const
TwistControllerParams twist_controller_params_
bool getParam(const std::string &key, std::string &s) const
#define ROS_WARN_COND(cond,...)
ros::Subscriber twist_sub_
std::vector< std::string > joints
static Time now()
boost::shared_ptr< dynamic_reconfigure::Server< cob_twist_controller::TwistControllerConfig > > reconfigure_server_
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
ros::Subscriber obstacle_distance_sub_
boost::recursive_mutex reconfig_mutex_
void checkSolverAndConstraints(cob_twist_controller::TwistControllerConfig &config)
#define ROS_ERROR(...)
std::vector< double > limits_vel
TFSIMD_FORCE_INLINE tfScalar length2() const
Quaternion normalized() const
void visualizeTwist(KDL::Twist twist)
boost::shared_ptr< cob_twist_controller::ControllerInterfaceBase > controller_interface_


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:00