diff_drive_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, PAL Robotics, S.L.
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 PAL Robotics 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 /*
36  * Author: Bence Magyar, Enrique Fernández
37  */
38 
39 #include <cmath>
41 #include <tf/transform_datatypes.h>
42 #include <urdf/urdfdom_compatibility.h>
43 #include <urdf_parser/urdf_parser.h>
44 
45 static double euclideanOfVectors(const urdf::Vector3& vec1, const urdf::Vector3& vec2)
46 {
47  return std::sqrt(std::pow(vec1.x-vec2.x,2) +
48  std::pow(vec1.y-vec2.y,2) +
49  std::pow(vec1.z-vec2.z,2));
50 }
51 
52 /*
53 * \brief Check that a link exists and has a geometry collision.
54 * \param link The link
55 * \return true if the link has a collision element with geometry
56 */
57 static bool hasCollisionGeometry(const urdf::LinkConstSharedPtr& link)
58 {
59  if (!link)
60  {
61  ROS_ERROR("Link pointer is null.");
62  return false;
63  }
64 
65  if (!link->collision)
66  {
67  ROS_ERROR_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf.");
68  return false;
69  }
70 
71  if (!link->collision->geometry)
72  {
73  ROS_ERROR_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf.");
74  return false;
75  }
76  return true;
77 }
78 
79 /*
80  * \brief Check if the link is modeled as a cylinder
81  * \param link Link
82  * \return true if the link is modeled as a Cylinder; false otherwise
83  */
84 static bool isCylinder(const urdf::LinkConstSharedPtr& link)
85 {
86  if (!hasCollisionGeometry(link))
87  {
88  return false;
89  }
90 
91  if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
92  {
93  ROS_DEBUG_STREAM("Link " << link->name << " does not have cylinder geometry");
94  return false;
95  }
96 
97  return true;
98 }
99 
100 /*
101  * \brief Check if the link is modeled as a sphere
102  * \param link Link
103  * \return true if the link is modeled as a Sphere; false otherwise
104  */
105 static bool isSphere(const urdf::LinkConstSharedPtr& link)
106 {
107  if (!hasCollisionGeometry(link))
108  {
109  return false;
110  }
111 
112  if (link->collision->geometry->type != urdf::Geometry::SPHERE)
113  {
114  ROS_DEBUG_STREAM("Link " << link->name << " does not have sphere geometry");
115  return false;
116  }
117 
118  return true;
119 }
120 
121 /*
122  * \brief Get the wheel radius
123  * \param [in] wheel_link Wheel link
124  * \param [out] wheel_radius Wheel radius [m]
125  * \return true if the wheel radius was found; false otherwise
126  */
127 static bool getWheelRadius(const urdf::LinkConstSharedPtr& wheel_link, double& wheel_radius)
128 {
129  if (isCylinder(wheel_link))
130  {
131  wheel_radius = (static_cast<urdf::Cylinder*>(wheel_link->collision->geometry.get()))->radius;
132  return true;
133  }
134  else if (isSphere(wheel_link))
135  {
136  wheel_radius = (static_cast<urdf::Sphere*>(wheel_link->collision->geometry.get()))->radius;
137  return true;
138  }
139 
140  ROS_ERROR_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder or sphere!");
141  return false;
142 }
143 
144 namespace diff_drive_controller{
145 
147  : open_loop_(false)
148  , command_struct_()
149  , wheel_separation_(0.0)
150  , wheel_radius_(0.0)
151  , wheel_separation_multiplier_(1.0)
152  , left_wheel_radius_multiplier_(1.0)
153  , right_wheel_radius_multiplier_(1.0)
154  , cmd_vel_timeout_(0.5)
155  , allow_multiple_cmd_vel_publishers_(true)
156  , base_frame_id_("base_link")
157  , odom_frame_id_("odom")
158  , enable_odom_tf_(true)
159  , wheel_joints_size_(0)
160  , publish_cmd_(false)
161  , publish_wheel_joint_controller_state_(false)
162  {
163  }
164 
166  ros::NodeHandle& root_nh,
167  ros::NodeHandle &controller_nh)
168  {
169  const std::string complete_ns = controller_nh.getNamespace();
170  std::size_t id = complete_ns.find_last_of("/");
171  name_ = complete_ns.substr(id + 1);
172 
173  // Get joint names from the parameter server
174  std::vector<std::string> left_wheel_names, right_wheel_names;
175  if (!getWheelNames(controller_nh, "left_wheel", left_wheel_names) ||
176  !getWheelNames(controller_nh, "right_wheel", right_wheel_names))
177  {
178  return false;
179  }
180 
181  if (left_wheel_names.size() != right_wheel_names.size())
182  {
184  "#left wheels (" << left_wheel_names.size() << ") != " <<
185  "#right wheels (" << right_wheel_names.size() << ").");
186  return false;
187  }
188  else
189  {
190  wheel_joints_size_ = left_wheel_names.size();
191 
194  }
195 
196  // Odometry related:
197  double publish_rate;
198  controller_nh.param("publish_rate", publish_rate, 50.0);
199  ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
200  << publish_rate << "Hz.");
201  publish_period_ = ros::Duration(1.0 / publish_rate);
202 
203  controller_nh.param("open_loop", open_loop_, open_loop_);
204 
205  controller_nh.param("wheel_separation_multiplier", wheel_separation_multiplier_, wheel_separation_multiplier_);
206  ROS_INFO_STREAM_NAMED(name_, "Wheel separation will be multiplied by "
207  << wheel_separation_multiplier_ << ".");
208 
209  if (controller_nh.hasParam("wheel_radius_multiplier"))
210  {
211  double wheel_radius_multiplier;
212  controller_nh.getParam("wheel_radius_multiplier", wheel_radius_multiplier);
213 
214  left_wheel_radius_multiplier_ = wheel_radius_multiplier;
215  right_wheel_radius_multiplier_ = wheel_radius_multiplier;
216  }
217  else
218  {
219  controller_nh.param("left_wheel_radius_multiplier", left_wheel_radius_multiplier_, left_wheel_radius_multiplier_);
220  controller_nh.param("right_wheel_radius_multiplier", right_wheel_radius_multiplier_, right_wheel_radius_multiplier_);
221  }
222 
223  ROS_INFO_STREAM_NAMED(name_, "Left wheel radius will be multiplied by "
225  ROS_INFO_STREAM_NAMED(name_, "Right wheel radius will be multiplied by "
227 
228  int velocity_rolling_window_size = 10;
229  controller_nh.param("velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
230  ROS_INFO_STREAM_NAMED(name_, "Velocity rolling window size of "
231  << velocity_rolling_window_size << ".");
232 
233  odometry_.setVelocityRollingWindowSize(velocity_rolling_window_size);
234 
235  // Twist command related:
236  controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
237  ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
238  << cmd_vel_timeout_ << "s.");
239 
240  controller_nh.param("allow_multiple_cmd_vel_publishers", allow_multiple_cmd_vel_publishers_, allow_multiple_cmd_vel_publishers_);
241  ROS_INFO_STREAM_NAMED(name_, "Allow mutiple cmd_vel publishers is "
242  << (allow_multiple_cmd_vel_publishers_?"enabled":"disabled"));
243 
244  controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
245  ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
246 
247  controller_nh.param("odom_frame_id", odom_frame_id_, odom_frame_id_);
248  ROS_INFO_STREAM_NAMED(name_, "Odometry frame_id set to " << odom_frame_id_);
249 
250  controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
251  ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
252 
253  // Velocity and acceleration limits:
254  controller_nh.param("linear/x/has_velocity_limits" , limiter_lin_.has_velocity_limits , limiter_lin_.has_velocity_limits );
255  controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
256  controller_nh.param("linear/x/has_jerk_limits" , limiter_lin_.has_jerk_limits , limiter_lin_.has_jerk_limits );
257  controller_nh.param("linear/x/max_velocity" , limiter_lin_.max_velocity , limiter_lin_.max_velocity );
258  controller_nh.param("linear/x/min_velocity" , limiter_lin_.min_velocity , -limiter_lin_.max_velocity );
259  controller_nh.param("linear/x/max_acceleration" , limiter_lin_.max_acceleration , limiter_lin_.max_acceleration );
260  controller_nh.param("linear/x/min_acceleration" , limiter_lin_.min_acceleration , -limiter_lin_.max_acceleration );
261  controller_nh.param("linear/x/max_jerk" , limiter_lin_.max_jerk , limiter_lin_.max_jerk );
262  controller_nh.param("linear/x/min_jerk" , limiter_lin_.min_jerk , -limiter_lin_.max_jerk );
263 
264  controller_nh.param("angular/z/has_velocity_limits" , limiter_ang_.has_velocity_limits , limiter_ang_.has_velocity_limits );
265  controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
266  controller_nh.param("angular/z/has_jerk_limits" , limiter_ang_.has_jerk_limits , limiter_ang_.has_jerk_limits );
267  controller_nh.param("angular/z/max_velocity" , limiter_ang_.max_velocity , limiter_ang_.max_velocity );
268  controller_nh.param("angular/z/min_velocity" , limiter_ang_.min_velocity , -limiter_ang_.max_velocity );
269  controller_nh.param("angular/z/max_acceleration" , limiter_ang_.max_acceleration , limiter_ang_.max_acceleration );
270  controller_nh.param("angular/z/min_acceleration" , limiter_ang_.min_acceleration , -limiter_ang_.max_acceleration );
271  controller_nh.param("angular/z/max_jerk" , limiter_ang_.max_jerk , limiter_ang_.max_jerk );
272  controller_nh.param("angular/z/min_jerk" , limiter_ang_.min_jerk , -limiter_ang_.max_jerk );
273 
274  // Publish limited velocity:
275  controller_nh.param("publish_cmd", publish_cmd_, publish_cmd_);
276 
277  // Publish wheel data:
278  controller_nh.param("publish_wheel_joint_controller_state", publish_wheel_joint_controller_state_, publish_wheel_joint_controller_state_);
279 
280  // If either parameter is not available, we need to look up the value in the URDF
281  bool lookup_wheel_separation = !controller_nh.getParam("wheel_separation", wheel_separation_);
282  bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheel_radius_);
283 
284  if (!setOdomParamsFromUrdf(root_nh,
285  left_wheel_names[0],
286  right_wheel_names[0],
287  lookup_wheel_separation,
288  lookup_wheel_radius))
289  {
290  return false;
291  }
292 
293  // Regardless of how we got the separation and radius, use them
294  // to set the odometry parameters
296  const double lwr = left_wheel_radius_multiplier_ * wheel_radius_;
297  const double rwr = right_wheel_radius_multiplier_ * wheel_radius_;
298  odometry_.setWheelParams(ws, lwr, rwr);
300  "Odometry params : wheel separation " << ws
301  << ", left wheel radius " << lwr
302  << ", right wheel radius " << rwr);
303 
304  setOdomPubFields(root_nh, controller_nh);
305 
306  if (publish_cmd_)
307  {
308  cmd_vel_pub_.reset(new realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped>(controller_nh, "cmd_vel_out", 100));
309  }
310 
311  // Wheel joint controller state:
313  {
314  controller_state_pub_.reset(new realtime_tools::RealtimePublisher<control_msgs::JointTrajectoryControllerState>(controller_nh, "wheel_joint_controller_state", 100));
315 
316  const size_t num_wheels = wheel_joints_size_ * 2;
317 
318  controller_state_pub_->msg_.joint_names.resize(num_wheels);
319 
320  controller_state_pub_->msg_.desired.positions.resize(num_wheels);
321  controller_state_pub_->msg_.desired.velocities.resize(num_wheels);
322  controller_state_pub_->msg_.desired.accelerations.resize(num_wheels);
323  controller_state_pub_->msg_.desired.effort.resize(num_wheels);
324 
325  controller_state_pub_->msg_.actual.positions.resize(num_wheels);
326  controller_state_pub_->msg_.actual.velocities.resize(num_wheels);
327  controller_state_pub_->msg_.actual.accelerations.resize(num_wheels);
328  controller_state_pub_->msg_.actual.effort.resize(num_wheels);
329 
330  controller_state_pub_->msg_.error.positions.resize(num_wheels);
331  controller_state_pub_->msg_.error.velocities.resize(num_wheels);
332  controller_state_pub_->msg_.error.accelerations.resize(num_wheels);
333  controller_state_pub_->msg_.error.effort.resize(num_wheels);
334 
335  for (size_t i = 0; i < wheel_joints_size_; ++i)
336  {
337  controller_state_pub_->msg_.joint_names[i] = left_wheel_names[i];
338  controller_state_pub_->msg_.joint_names[i + wheel_joints_size_] = right_wheel_names[i];
339  }
340 
341  vel_left_previous_.resize(wheel_joints_size_, 0.0);
342  vel_right_previous_.resize(wheel_joints_size_, 0.0);
343  }
344 
345  // Get the joint object to use in the realtime loop
346  for (size_t i = 0; i < wheel_joints_size_; ++i)
347  {
349  "Adding left wheel with joint name: " << left_wheel_names[i]
350  << " and right wheel with joint name: " << right_wheel_names[i]);
351  left_wheel_joints_[i] = hw->getHandle(left_wheel_names[i]); // throws on failure
352  right_wheel_joints_[i] = hw->getHandle(right_wheel_names[i]); // throws on failure
353  }
354 
355  sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this);
356 
357  // Initialize dynamic parameters
358  DynamicParams dynamic_params;
362 
363  dynamic_params.publish_rate = publish_rate;
364  dynamic_params.enable_odom_tf = enable_odom_tf_;
365 
366  dynamic_params_.writeFromNonRT(dynamic_params);
367 
368  // Initialize dynamic_reconfigure server
369  DiffDriveControllerConfig config;
370  config.left_wheel_radius_multiplier = left_wheel_radius_multiplier_;
371  config.right_wheel_radius_multiplier = right_wheel_radius_multiplier_;
372  config.wheel_separation_multiplier = wheel_separation_multiplier_;
373 
374  config.publish_rate = publish_rate;
375  config.enable_odom_tf = enable_odom_tf_;
376 
377  dyn_reconf_server_ = std::make_shared<ReconfigureServer>(dyn_reconf_server_mutex_, controller_nh);
378 
379  // Update parameters
380  dyn_reconf_server_mutex_.lock();
381  dyn_reconf_server_->updateConfig(config);
382  dyn_reconf_server_mutex_.unlock();
383 
384  dyn_reconf_server_->setCallback(boost::bind(&DiffDriveController::reconfCallback, this, _1, _2));
385 
386  return true;
387  }
388 
389  void DiffDriveController::update(const ros::Time& time, const ros::Duration& period)
390  {
391  // update parameter from dynamic reconf
393 
394  // Apply (possibly new) multipliers:
396  const double lwr = left_wheel_radius_multiplier_ * wheel_radius_;
397  const double rwr = right_wheel_radius_multiplier_ * wheel_radius_;
398 
399  odometry_.setWheelParams(ws, lwr, rwr);
400 
401  // COMPUTE AND PUBLISH ODOMETRY
402  if (open_loop_)
403  {
405  }
406  else
407  {
408  double left_pos = 0.0;
409  double right_pos = 0.0;
410  for (size_t i = 0; i < wheel_joints_size_; ++i)
411  {
412  const double lp = left_wheel_joints_[i].getPosition();
413  const double rp = right_wheel_joints_[i].getPosition();
414  if (std::isnan(lp) || std::isnan(rp))
415  return;
416 
417  left_pos += lp;
418  right_pos += rp;
419  }
420  left_pos /= wheel_joints_size_;
421  right_pos /= wheel_joints_size_;
422 
423  // Estimate linear and angular velocity using joint information
424  odometry_.update(left_pos, right_pos, time);
425  }
426 
427  // Publish odometry message
429  {
431  // Compute and store orientation info
432  const geometry_msgs::Quaternion orientation(
434 
435  // Populate odom message and publish
436  if (odom_pub_->trylock())
437  {
438  odom_pub_->msg_.header.stamp = time;
439  odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
440  odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
441  odom_pub_->msg_.pose.pose.orientation = orientation;
442  odom_pub_->msg_.twist.twist.linear.x = odometry_.getLinear();
443  odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular();
444  odom_pub_->unlockAndPublish();
445  }
446 
447  // Publish tf /odom frame
448  if (enable_odom_tf_ && tf_odom_pub_->trylock())
449  {
450  geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0];
451  odom_frame.header.stamp = time;
452  odom_frame.transform.translation.x = odometry_.getX();
453  odom_frame.transform.translation.y = odometry_.getY();
454  odom_frame.transform.rotation = orientation;
455  tf_odom_pub_->unlockAndPublish();
456  }
457  }
458 
459  // MOVE ROBOT
460  // Retreive current velocity command and time step:
461  Commands curr_cmd = *(command_.readFromRT());
462  const double dt = (time - curr_cmd.stamp).toSec();
463 
464  // Brake if cmd_vel has timeout:
465  if (dt > cmd_vel_timeout_)
466  {
467  curr_cmd.lin = 0.0;
468  curr_cmd.ang = 0.0;
469  }
470 
471  // Limit velocities and accelerations:
472  const double cmd_dt(period.toSec());
473 
474  limiter_lin_.limit(curr_cmd.lin, last0_cmd_.lin, last1_cmd_.lin, cmd_dt);
475  limiter_ang_.limit(curr_cmd.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt);
476 
478  last0_cmd_ = curr_cmd;
479 
480  // Publish limited velocity:
481  if (publish_cmd_ && cmd_vel_pub_ && cmd_vel_pub_->trylock())
482  {
483  cmd_vel_pub_->msg_.header.stamp = time;
484  cmd_vel_pub_->msg_.twist.linear.x = curr_cmd.lin;
485  cmd_vel_pub_->msg_.twist.angular.z = curr_cmd.ang;
486  cmd_vel_pub_->unlockAndPublish();
487  }
488 
489  // Compute wheels velocities:
490  const double vel_left = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/lwr;
491  const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/rwr;
492 
493  // Set wheels velocities:
494  for (size_t i = 0; i < wheel_joints_size_; ++i)
495  {
496  left_wheel_joints_[i].setCommand(vel_left);
497  right_wheel_joints_[i].setCommand(vel_right);
498  }
499 
500  publishWheelData(time, period, curr_cmd, ws, lwr, rwr);
501  time_previous_ = time;
502  }
503 
505  {
506  brake();
507 
508  // Register starting time used to keep fixed rate
510  time_previous_ = time;
511 
512  odometry_.init(time);
513  }
514 
516  {
517  brake();
518  }
519 
521  {
522  const double vel = 0.0;
523  for (size_t i = 0; i < wheel_joints_size_; ++i)
524  {
525  left_wheel_joints_[i].setCommand(vel);
526  right_wheel_joints_[i].setCommand(vel);
527  }
528  }
529 
530  void DiffDriveController::cmdVelCallback(const geometry_msgs::Twist& command)
531  {
532  if (isRunning())
533  {
534  // check that we don't have multiple publishers on the command topic
536  {
538  << " publishers. Only 1 publisher is allowed. Going to brake.");
539  brake();
540  return;
541  }
542 
543  if(!std::isfinite(command.angular.z) || !std::isfinite(command.angular.x))
544  {
545  ROS_WARN_THROTTLE(1.0, "Received NaN in velocity command. Ignoring.");
546  return;
547  }
548 
549  command_struct_.ang = command.angular.z;
550  command_struct_.lin = command.linear.x;
552  command_.writeFromNonRT (command_struct_);
554  "Added values to command. "
555  << "Ang: " << command_struct_.ang << ", "
556  << "Lin: " << command_struct_.lin << ", "
557  << "Stamp: " << command_struct_.stamp);
558  }
559  else
560  {
561  ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
562  }
563  }
564 
566  const std::string& wheel_param,
567  std::vector<std::string>& wheel_names)
568  {
569  XmlRpc::XmlRpcValue wheel_list;
570  if (!controller_nh.getParam(wheel_param, wheel_list))
571  {
573  "Couldn't retrieve wheel param '" << wheel_param << "'.");
574  return false;
575  }
576 
577  if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
578  {
579  if (wheel_list.size() == 0)
580  {
582  "Wheel param '" << wheel_param << "' is an empty list");
583  return false;
584  }
585 
586  for (int i = 0; i < wheel_list.size(); ++i)
587  {
588  if (wheel_list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
589  {
591  "Wheel param '" << wheel_param << "' #" << i <<
592  " isn't a string.");
593  return false;
594  }
595  }
596 
597  wheel_names.resize(wheel_list.size());
598  for (int i = 0; i < wheel_list.size(); ++i)
599  {
600  wheel_names[i] = static_cast<std::string>(wheel_list[i]);
601  }
602  }
603  else if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeString)
604  {
605  wheel_names.push_back(wheel_list);
606  }
607  else
608  {
610  "Wheel param '" << wheel_param <<
611  "' is neither a list of strings nor a string.");
612  return false;
613  }
614 
615  return true;
616  }
617 
619  const std::string& left_wheel_name,
620  const std::string& right_wheel_name,
621  bool lookup_wheel_separation,
622  bool lookup_wheel_radius)
623  {
624  if (!(lookup_wheel_separation || lookup_wheel_radius))
625  {
626  // Short-circuit in case we don't need to look up anything, so we don't have to parse the URDF
627  return true;
628  }
629 
630  // Parse robot description
631  const std::string model_param_name = "robot_description";
632  bool res = root_nh.hasParam(model_param_name);
633  std::string robot_model_str="";
634  if (!res || !root_nh.getParam(model_param_name,robot_model_str))
635  {
636  ROS_ERROR_NAMED(name_, "Robot description couldn't be retrieved from param server.");
637  return false;
638  }
639 
640  urdf::ModelInterfaceSharedPtr model(urdf::parseURDF(robot_model_str));
641 
642  urdf::JointConstSharedPtr left_wheel_joint(model->getJoint(left_wheel_name));
643  urdf::JointConstSharedPtr right_wheel_joint(model->getJoint(right_wheel_name));
644 
645  if (lookup_wheel_separation)
646  {
647  // Get wheel separation
648  if (!left_wheel_joint)
649  {
650  ROS_ERROR_STREAM_NAMED(name_, left_wheel_name
651  << " couldn't be retrieved from model description");
652  return false;
653  }
654 
655  if (!right_wheel_joint)
656  {
657  ROS_ERROR_STREAM_NAMED(name_, right_wheel_name
658  << " couldn't be retrieved from model description");
659  return false;
660  }
661 
662  ROS_INFO_STREAM("left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x << ","
663  << left_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
664  << left_wheel_joint->parent_to_joint_origin_transform.position.z);
665  ROS_INFO_STREAM("right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x << ","
666  << right_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
667  << right_wheel_joint->parent_to_joint_origin_transform.position.z);
668 
669  wheel_separation_ = euclideanOfVectors(left_wheel_joint->parent_to_joint_origin_transform.position,
670  right_wheel_joint->parent_to_joint_origin_transform.position);
671 
672  }
673 
674  if (lookup_wheel_radius)
675  {
676  // Get wheel radius
677  if (!getWheelRadius(model->getLink(left_wheel_joint->child_link_name), wheel_radius_))
678  {
679  ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve " << left_wheel_name << " wheel radius");
680  return false;
681  }
682  }
683 
684  return true;
685  }
686 
688  {
689  // Get and check params for covariances
690  XmlRpc::XmlRpcValue pose_cov_list;
691  controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
693  ROS_ASSERT(pose_cov_list.size() == 6);
694  for (int i = 0; i < pose_cov_list.size(); ++i)
695  ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
696 
697  XmlRpc::XmlRpcValue twist_cov_list;
698  controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
700  ROS_ASSERT(twist_cov_list.size() == 6);
701  for (int i = 0; i < twist_cov_list.size(); ++i)
702  ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
703 
704  // Setup odometry realtime publisher + odom message constant fields
705  odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
706  odom_pub_->msg_.header.frame_id = odom_frame_id_;
707  odom_pub_->msg_.child_frame_id = base_frame_id_;
708  odom_pub_->msg_.pose.pose.position.z = 0;
709  odom_pub_->msg_.pose.covariance = {
710  static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
711  0., static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
712  0., 0., static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
713  0., 0., 0., static_cast<double>(pose_cov_list[3]), 0., 0.,
714  0., 0., 0., 0., static_cast<double>(pose_cov_list[4]), 0.,
715  0., 0., 0., 0., 0., static_cast<double>(pose_cov_list[5]) };
716  odom_pub_->msg_.twist.twist.linear.y = 0;
717  odom_pub_->msg_.twist.twist.linear.z = 0;
718  odom_pub_->msg_.twist.twist.angular.x = 0;
719  odom_pub_->msg_.twist.twist.angular.y = 0;
720  odom_pub_->msg_.twist.covariance = {
721  static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
722  0., static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
723  0., 0., static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
724  0., 0., 0., static_cast<double>(twist_cov_list[3]), 0., 0.,
725  0., 0., 0., 0., static_cast<double>(twist_cov_list[4]), 0.,
726  0., 0., 0., 0., 0., static_cast<double>(twist_cov_list[5]) };
727  tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
728  tf_odom_pub_->msg_.transforms.resize(1);
729  tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
730  tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_;
731  tf_odom_pub_->msg_.transforms[0].header.frame_id = odom_frame_id_;
732  }
733 
734  void DiffDriveController::reconfCallback(DiffDriveControllerConfig& config, uint32_t /*level*/)
735  {
736  DynamicParams dynamic_params;
737  dynamic_params.left_wheel_radius_multiplier = config.left_wheel_radius_multiplier;
738  dynamic_params.right_wheel_radius_multiplier = config.right_wheel_radius_multiplier;
739  dynamic_params.wheel_separation_multiplier = config.wheel_separation_multiplier;
740 
741  dynamic_params.publish_rate = config.publish_rate;
742 
743  dynamic_params.enable_odom_tf = config.enable_odom_tf;
744 
745  dynamic_params_.writeFromNonRT(dynamic_params);
746 
747  ROS_INFO_STREAM_NAMED(name_, "Dynamic Reconfigure:\n" << dynamic_params);
748  }
749 
751  {
752  // Retreive dynamic params:
753  const DynamicParams dynamic_params = *(dynamic_params_.readFromRT());
754 
758 
759  publish_period_ = ros::Duration(1.0 / dynamic_params.publish_rate);
760  enable_odom_tf_ = dynamic_params.enable_odom_tf;
761  }
762 
763  void DiffDriveController::publishWheelData(const ros::Time& time, const ros::Duration& period, Commands& curr_cmd,
764  double wheel_separation, double left_wheel_radius, double right_wheel_radius)
765  {
767  {
768  const double cmd_dt(period.toSec());
769 
770  // Compute desired wheels velocities, that is before applying limits:
771  const double vel_left_desired = (curr_cmd.lin - curr_cmd.ang * wheel_separation / 2.0) / left_wheel_radius;
772  const double vel_right_desired = (curr_cmd.lin + curr_cmd.ang * wheel_separation / 2.0) / right_wheel_radius;
773  controller_state_pub_->msg_.header.stamp = time;
774 
775  for (size_t i = 0; i < wheel_joints_size_; ++i)
776  {
777  const double control_duration = (time - time_previous_).toSec();
778 
779  const double left_wheel_acc = (left_wheel_joints_[i].getVelocity() - vel_left_previous_[i]) / control_duration;
780  const double right_wheel_acc = (right_wheel_joints_[i].getVelocity() - vel_right_previous_[i]) / control_duration;
781 
782  // Actual
783  controller_state_pub_->msg_.actual.positions[i] = left_wheel_joints_[i].getPosition();
784  controller_state_pub_->msg_.actual.velocities[i] = left_wheel_joints_[i].getVelocity();
785  controller_state_pub_->msg_.actual.accelerations[i] = left_wheel_acc;
786  controller_state_pub_->msg_.actual.effort[i] = left_wheel_joints_[i].getEffort();
787 
788  controller_state_pub_->msg_.actual.positions[i + wheel_joints_size_] = right_wheel_joints_[i].getPosition();
789  controller_state_pub_->msg_.actual.velocities[i + wheel_joints_size_] = right_wheel_joints_[i].getVelocity();
790  controller_state_pub_->msg_.actual.accelerations[i + wheel_joints_size_] = right_wheel_acc;
791  controller_state_pub_->msg_.actual.effort[i+ wheel_joints_size_] = right_wheel_joints_[i].getEffort();
792 
793  // Desired
794  controller_state_pub_->msg_.desired.positions[i] += vel_left_desired * cmd_dt;
795  controller_state_pub_->msg_.desired.velocities[i] = vel_left_desired;
796  controller_state_pub_->msg_.desired.accelerations[i] = (vel_left_desired - vel_left_desired_previous_) * cmd_dt;
797  controller_state_pub_->msg_.desired.effort[i] = std::numeric_limits<double>::quiet_NaN();
798 
799  controller_state_pub_->msg_.desired.positions[i + wheel_joints_size_] += vel_right_desired * cmd_dt;
800  controller_state_pub_->msg_.desired.velocities[i + wheel_joints_size_] = vel_right_desired;
801  controller_state_pub_->msg_.desired.accelerations[i + wheel_joints_size_] = (vel_right_desired - vel_right_desired_previous_) * cmd_dt;
802  controller_state_pub_->msg_.desired.effort[i+ wheel_joints_size_] = std::numeric_limits<double>::quiet_NaN();
803 
804  // Error
805  controller_state_pub_->msg_.error.positions[i] = controller_state_pub_->msg_.desired.positions[i] -
806  controller_state_pub_->msg_.actual.positions[i];
807  controller_state_pub_->msg_.error.velocities[i] = controller_state_pub_->msg_.desired.velocities[i] -
808  controller_state_pub_->msg_.actual.velocities[i];
809  controller_state_pub_->msg_.error.accelerations[i] = controller_state_pub_->msg_.desired.accelerations[i] -
810  controller_state_pub_->msg_.actual.accelerations[i];
811  controller_state_pub_->msg_.error.effort[i] = controller_state_pub_->msg_.desired.effort[i] -
812  controller_state_pub_->msg_.actual.effort[i];
813 
814  controller_state_pub_->msg_.error.positions[i + wheel_joints_size_] = controller_state_pub_->msg_.desired.positions[i + wheel_joints_size_] -
815  controller_state_pub_->msg_.actual.positions[i + wheel_joints_size_];
816  controller_state_pub_->msg_.error.velocities[i + wheel_joints_size_] = controller_state_pub_->msg_.desired.velocities[i + wheel_joints_size_] -
817  controller_state_pub_->msg_.actual.velocities[i + wheel_joints_size_];
818  controller_state_pub_->msg_.error.accelerations[i + wheel_joints_size_] = controller_state_pub_->msg_.desired.accelerations[i + wheel_joints_size_] -
819  controller_state_pub_->msg_.actual.accelerations[i + wheel_joints_size_];
820  controller_state_pub_->msg_.error.effort[i+ wheel_joints_size_] = controller_state_pub_->msg_.desired.effort[i + wheel_joints_size_] -
821  controller_state_pub_->msg_.actual.effort[i + wheel_joints_size_];
822 
823  // Save previous velocities to compute acceleration
824  vel_left_previous_[i] = left_wheel_joints_[i].getVelocity();
825  vel_right_previous_[i] = right_wheel_joints_[i].getVelocity();
826  vel_left_desired_previous_ = vel_left_desired;
827  vel_right_desired_previous_ = vel_right_desired;
828  }
829 
830  controller_state_pub_->unlockAndPublish();
831  }
832  }
833 
834 } // namespace diff_drive_controller
realtime_tools::RealtimeBuffer< Commands > command_
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
void updateDynamicParams()
Update the dynamic parameters in the RT loop.
std::vector< hardware_interface::JointHandle > left_wheel_joints_
Hardware handles:
static bool hasCollisionGeometry(const urdf::LinkConstSharedPtr &link)
bool update(double left_pos, double right_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.
Definition: odometry.cpp:76
#define ROS_DEBUG_STREAM_NAMED(name, args)
double wheel_radius_
Wheel radius (assuming it&#39;s the same for the left and right wheels):
#define ROS_ERROR_STREAM_NAMED(name, args)
static bool getWheelRadius(const urdf::LinkConstSharedPtr &wheel_link, double &wheel_radius)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string odom_frame_id_
Frame to use for odometry and odom tf:
static bool isCylinder(const urdf::LinkConstSharedPtr &link)
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
uint32_t getNumPublishers() const
size_t wheel_joints_size_
Number of wheel joints:
#define ROS_INFO_STREAM_NAMED(name, args)
bool getWheelNames(ros::NodeHandle &controller_nh, const std::string &wheel_param, std::vector< std::string > &wheel_names)
Get the wheel names from a wheel param.
double getY() const
y position getter
Definition: odometry.h:119
double getAngular() const
angular velocity getter
Definition: odometry.h:137
#define ROS_ERROR_STREAM_THROTTLE_NAMED(period, name, args)
std::shared_ptr< realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > > controller_state_pub_
Controller state publisher.
std::vector< double > vel_left_previous_
Previous velocities from the encoders:
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Type const & getType() const
static bool isSphere(const urdf::LinkConstSharedPtr &link)
std::vector< hardware_interface::JointHandle > right_wheel_joints_
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
double getHeading() const
heading getter
Definition: odometry.h:101
#define ROS_WARN_THROTTLE(period,...)
void starting(const ros::Time &time)
Starts controller.
double vel_left_desired_previous_
Previous velocities from the encoders:
bool getParam(const std::string &key, std::string &s) const
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::TwistStamped > > cmd_vel_pub_
Publish executed commands.
void init(const ros::Time &time)
Initialize the odometry.
Definition: odometry.cpp:69
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius)
Sets the wheel parameters: radius and separation.
Definition: odometry.cpp:126
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
realtime_tools::RealtimeBuffer< DynamicParams > dynamic_params_
#define ROS_DEBUG_STREAM(args)
bool publish_wheel_joint_controller_state_
Publish wheel data:
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
Definition: odometry.cpp:133
bool hasParam(const std::string &key) const
ros::Duration publish_period_
Odometry related:
JointHandle getHandle(const std::string &name)
void publishWheelData(const ros::Time &time, const ros::Duration &period, Commands &curr_cmd, double wheel_separation, double left_wheel_radius, double right_wheel_radius)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
const std::string & getNamespace() const
double getLinear() const
linear velocity getter
Definition: odometry.h:128
static double euclideanOfVectors(const urdf::Vector3 &vec1, const urdf::Vector3 &vec2)
std::shared_ptr< ReconfigureServer > dyn_reconf_server_
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
Definition: odometry.cpp:114
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
#define ROS_ERROR_NAMED(name,...)
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string &left_wheel_name, const std::string &right_wheel_name, bool lookup_wheel_separation, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
static Time now()
double getX() const
x position getter
Definition: odometry.h:110
bool enable_odom_tf_
Whether to publish odometry to tf or not:
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
void reconfCallback(DiffDriveControllerConfig &config, uint32_t)
Callback for dynamic_reconfigure server.
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
#define ROS_ERROR(...)
double limit(double &v, double v0, double v1, double dt)
Limit the velocity and acceleration.
void stopping(const ros::Time &)
Stops controller.
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
std::string base_frame_id_
Frame to use for the robot base:


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri Feb 3 2023 03:19:01