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


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri May 24 2024 02:41:04