ackermann_steering_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: Masaru Morita, Bence Magyar, Enrique Fernández
37  */
38 
39 #include <cmath>
41 #include <tf/transform_datatypes.h>
42 #include <urdf_parser/urdf_parser.h>
43 
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 if the link is modeled as a cylinder
55  * \param link Link
56  * \return true if the link is modeled as a Cylinder; false otherwise
57  */
58 static bool isCylinder(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 
78  if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
79  {
80  ROS_ERROR_STREAM("Link " << link->name << " does not have cylinder geometry");
81  return false;
82  }
83 
84  return true;
85 }
86 
87 /*
88  * \brief Get the wheel radius
89  * \param [in] wheel_link Wheel link
90  * \param [out] wheel_radius Wheel radius [m]
91  * \return true if the wheel radius was found; false other
92 wise
93  */
94 static bool getWheelRadius(const urdf::LinkConstSharedPtr& wheel_link, double& wheel_radius)
95 {
96  if (!isCylinder(wheel_link))
97  {
98  ROS_ERROR_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder!");
99  return false;
100  }
101 
102  wheel_radius = (static_cast<urdf::Cylinder*>(wheel_link->collision->geometry.get()))->radius;
103  return true;
104 }
105 
107 
109  : open_loop_(false)
110  , command_struct_()
111  , wheel_separation_h_(0.0)
112  , wheel_radius_(0.0)
113  , wheel_separation_h_multiplier_(1.0)
114  , wheel_radius_multiplier_(1.0)
115  , steer_pos_multiplier_(1.0)
116  , cmd_vel_timeout_(0.5)
117  , allow_multiple_cmd_vel_publishers_(true)
118  , base_frame_id_("base_link")
119  , odom_frame_id_("odom")
120  , enable_odom_tf_(true)
121  , wheel_joints_size_(0)
122  {
123  }
124 
126  ros::NodeHandle& root_nh,
127  ros::NodeHandle& controller_nh)
128  {
131  typedef hardware_interface::JointStateInterface StateIface;
132 
133  // get multiple types of hardware_interface
134  VelIface *vel_joint_if = robot_hw->get<VelIface>(); // vel for wheels
135  PosIface *pos_joint_if = robot_hw->get<PosIface>(); // pos for steers
136 
137  const std::string complete_ns = controller_nh.getNamespace();
138 
139  std::size_t id = complete_ns.find_last_of("/");
140  name_ = complete_ns.substr(id + 1);
141 
142  //-- single rear wheel joint
143  std::string rear_wheel_name = "rear_wheel_joint";
144  controller_nh.param("rear_wheel", rear_wheel_name, rear_wheel_name);
145 
146  //-- single front steer joint
147  std::string front_steer_name = "front_steer_joint";
148  controller_nh.param("front_steer", front_steer_name, front_steer_name);
149 
150 
151  // Odometry related:
152  double publish_rate;
153  controller_nh.param("publish_rate", publish_rate, 50.0);
154  ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
155  << publish_rate << "Hz.");
156  publish_period_ = ros::Duration(1.0 / publish_rate);
157 
158  controller_nh.param("open_loop", open_loop_, open_loop_);
159 
160  controller_nh.param("wheel_separation_h_multiplier", wheel_separation_h_multiplier_, wheel_separation_h_multiplier_);
161  ROS_INFO_STREAM_NAMED(name_, "Wheel separation height will be multiplied by "
163 
164  controller_nh.param("wheel_radius_multiplier", wheel_radius_multiplier_, wheel_radius_multiplier_);
165  ROS_INFO_STREAM_NAMED(name_, "Wheel radius will be multiplied by "
166  << wheel_radius_multiplier_ << ".");
167 
168  controller_nh.param("steer_pos_multiplier", steer_pos_multiplier_, steer_pos_multiplier_);
169  ROS_INFO_STREAM_NAMED(name_, "Steer pos will be multiplied by "
170  << steer_pos_multiplier_ << ".");
171 
172  int velocity_rolling_window_size = 10;
173  controller_nh.param("velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
174  ROS_INFO_STREAM_NAMED(name_, "Velocity rolling window size of "
175  << velocity_rolling_window_size << ".");
176 
177  odometry_.setVelocityRollingWindowSize(velocity_rolling_window_size);
178 
179  // Twist command related:
180  controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
181  ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
182  << cmd_vel_timeout_ << "s.");
183 
184  controller_nh.param("allow_multiple_cmd_vel_publishers", allow_multiple_cmd_vel_publishers_, allow_multiple_cmd_vel_publishers_);
185  ROS_INFO_STREAM_NAMED(name_, "Allow mutiple cmd_vel publishers is "
186  << (allow_multiple_cmd_vel_publishers_?"enabled":"disabled"));
187 
188  controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
189  ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
190 
191  controller_nh.param("odom_frame_id", odom_frame_id_, odom_frame_id_);
192  ROS_INFO_STREAM_NAMED(name_, "Odometry frame_id set to " << odom_frame_id_);
193 
194  controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
195  ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
196 
197  // Velocity and acceleration limits:
198  controller_nh.param("linear/x/has_velocity_limits" , limiter_lin_.has_velocity_limits , limiter_lin_.has_velocity_limits );
199  controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
200  controller_nh.param("linear/x/has_jerk_limits" , limiter_lin_.has_jerk_limits , limiter_lin_.has_jerk_limits );
201  controller_nh.param("linear/x/max_velocity" , limiter_lin_.max_velocity , limiter_lin_.max_velocity );
202  controller_nh.param("linear/x/min_velocity" , limiter_lin_.min_velocity , -limiter_lin_.max_velocity );
203  controller_nh.param("linear/x/max_acceleration" , limiter_lin_.max_acceleration , limiter_lin_.max_acceleration );
204  controller_nh.param("linear/x/min_acceleration" , limiter_lin_.min_acceleration , -limiter_lin_.max_acceleration );
205  controller_nh.param("linear/x/max_jerk" , limiter_lin_.max_jerk , limiter_lin_.max_jerk );
206  controller_nh.param("linear/x/min_jerk" , limiter_lin_.min_jerk , -limiter_lin_.max_jerk );
207 
208  controller_nh.param("angular/z/has_velocity_limits" , limiter_ang_.has_velocity_limits , limiter_ang_.has_velocity_limits );
209  controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
210  controller_nh.param("angular/z/has_jerk_limits" , limiter_ang_.has_jerk_limits , limiter_ang_.has_jerk_limits );
211  controller_nh.param("angular/z/max_velocity" , limiter_ang_.max_velocity , limiter_ang_.max_velocity );
212  controller_nh.param("angular/z/min_velocity" , limiter_ang_.min_velocity , -limiter_ang_.max_velocity );
213  controller_nh.param("angular/z/max_acceleration" , limiter_ang_.max_acceleration , limiter_ang_.max_acceleration );
214  controller_nh.param("angular/z/min_acceleration" , limiter_ang_.min_acceleration , -limiter_ang_.max_acceleration );
215  controller_nh.param("angular/z/max_jerk" , limiter_ang_.max_jerk , limiter_ang_.max_jerk );
216  controller_nh.param("angular/z/min_jerk" , limiter_ang_.min_jerk , -limiter_ang_.max_jerk );
217 
218  // If either parameter is not available, we need to look up the value in the URDF
219  bool lookup_wheel_separation_h = !controller_nh.getParam("wheel_separation_h", wheel_separation_h_);
220  bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheel_radius_);
221 
222  if (!setOdomParamsFromUrdf(root_nh,
223  rear_wheel_name,
224  front_steer_name,
225  lookup_wheel_separation_h,
226  lookup_wheel_radius))
227  {
228  return false;
229  }
230 
231  // Regardless of how we got the separation and radius, use them
232  // to set the odometry parameters
234  const double wr = wheel_radius_multiplier_ * wheel_radius_;
235  odometry_.setWheelParams(ws_h, wr);
237  "Odometry params : wheel separation height " << ws_h
238  << ", wheel radius " << wr);
239 
240  setOdomPubFields(root_nh, controller_nh);
241 
242  //-- rear wheel
243  //---- handles need to be previously registerd in ackermann_steering_test.cpp
245  "Adding the rear wheel with joint name: " << rear_wheel_name);
246  rear_wheel_joint_ = vel_joint_if->getHandle(rear_wheel_name); // throws on failure
247  //-- front steer
249  "Adding the front steer with joint name: " << front_steer_name);
250  front_steer_joint_ = pos_joint_if->getHandle(front_steer_name); // throws on failure
252  "Adding the subscriber: cmd_vel");
253  sub_command_ = controller_nh.subscribe("cmd_vel", 1, &AckermannSteeringController::cmdVelCallback, this);
254  ROS_INFO_STREAM_NAMED(name_, "Finished controller initialization");
255 
256  return true;
257  }
258 
260  {
261  // COMPUTE AND PUBLISH ODOMETRY
262  if (open_loop_)
263  {
265  }
266  else
267  {
268  double wheel_pos = rear_wheel_joint_.getPosition();
269  double steer_pos = front_steer_joint_.getPosition();
270 
271  if (std::isnan(wheel_pos) || std::isnan(steer_pos))
272  return;
273 
274  // Estimate linear and angular velocity using joint information
275  steer_pos = steer_pos * steer_pos_multiplier_;
276  odometry_.update(wheel_pos, steer_pos, time);
277  }
278 
279  // Publish odometry message
281  {
283  // Compute and store orientation info
284  const geometry_msgs::Quaternion orientation(
286 
287  // Populate odom message and publish
288  if (odom_pub_->trylock())
289  {
290  odom_pub_->msg_.header.stamp = time;
291  odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
292  odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
293  odom_pub_->msg_.pose.pose.orientation = orientation;
294  odom_pub_->msg_.twist.twist.linear.x = odometry_.getLinear();
295  odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular();
296  odom_pub_->unlockAndPublish();
297  }
298 
299  // Publish tf /odom frame
300  if (enable_odom_tf_ && tf_odom_pub_->trylock())
301  {
302  geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0];
303  odom_frame.header.stamp = time;
304  odom_frame.transform.translation.x = odometry_.getX();
305  odom_frame.transform.translation.y = odometry_.getY();
306  odom_frame.transform.rotation = orientation;
307  tf_odom_pub_->unlockAndPublish();
308  }
309  }
310 
311  // MOVE ROBOT
312  // Retreive current velocity command and time step:
313  Commands curr_cmd = *(command_.readFromRT());
314  const double dt = (time - curr_cmd.stamp).toSec();
315 
316  // Brake if cmd_vel has timeout:
317  if (dt > cmd_vel_timeout_)
318  {
319  curr_cmd.lin = 0.0;
320  curr_cmd.ang = 0.0;
321  }
322 
323  // Limit velocities and accelerations:
324  const double cmd_dt(period.toSec());
325 
326  limiter_lin_.limit(curr_cmd.lin, last0_cmd_.lin, last1_cmd_.lin, cmd_dt);
327  limiter_ang_.limit(curr_cmd.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt);
328 
330  last0_cmd_ = curr_cmd;
331 
332  // Set Command
333  const double wheel_vel = curr_cmd.lin/wheel_radius_; // omega = linear_vel / radius
334  rear_wheel_joint_.setCommand(wheel_vel);
336 
337  }
338 
340  {
341  brake();
342 
343  // Register starting time used to keep fixed rate
345 
346  odometry_.init(time);
347  }
348 
350  {
351  brake();
352  }
353 
355  {
356  const double steer_pos = 0.0;
357  const double wheel_vel = 0.0;
358 
359  rear_wheel_joint_.setCommand(steer_pos);
360  front_steer_joint_.setCommand(wheel_vel);
361  }
362 
363  void AckermannSteeringController::cmdVelCallback(const geometry_msgs::Twist& command)
364  {
365  if (isRunning())
366  {
367  // check that we don't have multiple publishers on the command topic
369  {
371  << " publishers. Only 1 publisher is allowed. Going to brake.");
372  brake();
373  return;
374  }
375 
376  command_struct_.ang = command.angular.z;
377  command_struct_.lin = command.linear.x;
381  "Added values to command. "
382  << "Ang: " << command_struct_.ang << ", "
383  << "Lin: " << command_struct_.lin << ", "
384  << "Stamp: " << command_struct_.stamp);
385  }
386  else
387  {
388  ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
389  }
390  }
391 
392 
394  const std::string rear_wheel_name,
395  const std::string front_steer_name,
396  bool lookup_wheel_separation_h,
397  bool lookup_wheel_radius)
398  {
399  if (!(lookup_wheel_separation_h || lookup_wheel_radius))
400  {
401  // Short-circuit in case we don't need to look up anything, so we don't have to parse the URDF
402  return true;
403  }
404 
405  // Parse robot description
406  const std::string model_param_name = "robot_description";
407  bool res = root_nh.hasParam(model_param_name);
408  std::string robot_model_str="";
409  if (!res || !root_nh.getParam(model_param_name,robot_model_str))
410  {
411  ROS_ERROR_NAMED(name_, "Robot descripion couldn't be retrieved from param server.");
412  return false;
413  }
414 
415  urdf::ModelInterfaceSharedPtr model(urdf::parseURDF(robot_model_str));
416 
417  urdf::JointConstSharedPtr rear_wheel_joint(model->getJoint(rear_wheel_name));
418  urdf::JointConstSharedPtr front_steer_joint(model->getJoint(front_steer_name));
419 
420  if (lookup_wheel_separation_h)
421  {
422  // Get wheel separation
423  if (!rear_wheel_joint)
424  {
425  ROS_ERROR_STREAM_NAMED(name_, rear_wheel_name
426  << " couldn't be retrieved from model description");
427  return false;
428  }
429 
430  if (!front_steer_joint)
431  {
432  ROS_ERROR_STREAM_NAMED(name_, front_steer_name
433  << " couldn't be retrieved from model description");
434  return false;
435  }
436 
437  ROS_INFO_STREAM("rear wheel to origin: "
438  << rear_wheel_joint->parent_to_joint_origin_transform.position.x << ","
439  << rear_wheel_joint->parent_to_joint_origin_transform.position.y << ", "
440  << rear_wheel_joint->parent_to_joint_origin_transform.position.z);
441 
442  ROS_INFO_STREAM("front steer to origin: "
443  << front_steer_joint->parent_to_joint_origin_transform.position.x << ","
444  << front_steer_joint->parent_to_joint_origin_transform.position.y << ", "
445  << front_steer_joint->parent_to_joint_origin_transform.position.z);
446 
447  wheel_separation_h_ = fabs(
448  rear_wheel_joint->parent_to_joint_origin_transform.position.x
449  - front_steer_joint->parent_to_joint_origin_transform.position.x);
450 
451  ROS_INFO_STREAM("Calculated wheel_separation_h: " << wheel_separation_h_);
452  }
453 
454  if (lookup_wheel_radius)
455  {
456  // Get wheel radius
457  if (!getWheelRadius(model->getLink(rear_wheel_joint->child_link_name), wheel_radius_))
458  {
459  ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve " << rear_wheel_name << " wheel radius");
460  return false;
461  }
462  ROS_INFO_STREAM("Retrieved wheel_radius: " << wheel_radius_);
463  }
464 
465  return true;
466  }
467 
469  {
470  // Get and check params for covariances
471  XmlRpc::XmlRpcValue pose_cov_list;
472  controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
474  ROS_ASSERT(pose_cov_list.size() == 6);
475  for (int i = 0; i < pose_cov_list.size(); ++i)
476  ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
477 
478  XmlRpc::XmlRpcValue twist_cov_list;
479  controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
481  ROS_ASSERT(twist_cov_list.size() == 6);
482  for (int i = 0; i < twist_cov_list.size(); ++i)
483  ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
484 
485  // Setup odometry realtime publisher + odom message constant fields
486  odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
487  odom_pub_->msg_.header.frame_id = odom_frame_id_;
488  odom_pub_->msg_.child_frame_id = base_frame_id_;
489  odom_pub_->msg_.pose.pose.position.z = 0;
490  odom_pub_->msg_.pose.covariance = {
491  static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
492  0., static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
493  0., 0., static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
494  0., 0., 0., static_cast<double>(pose_cov_list[3]), 0., 0.,
495  0., 0., 0., 0., static_cast<double>(pose_cov_list[4]), 0.,
496  0., 0., 0., 0., 0., static_cast<double>(pose_cov_list[5]) };
497  odom_pub_->msg_.twist.twist.linear.y = 0;
498  odom_pub_->msg_.twist.twist.linear.z = 0;
499  odom_pub_->msg_.twist.twist.angular.x = 0;
500  odom_pub_->msg_.twist.twist.angular.y = 0;
501  odom_pub_->msg_.twist.covariance = {
502  static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
503  0., static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
504  0., 0., static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
505  0., 0., 0., static_cast<double>(twist_cov_list[3]), 0., 0.,
506  0., 0., 0., 0., static_cast<double>(twist_cov_list[4]), 0.,
507  0., 0., 0., 0., 0., static_cast<double>(twist_cov_list[5]) };
508  tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
509  tf_odom_pub_->msg_.transforms.resize(1);
510  tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
511  tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_;
512  tf_odom_pub_->msg_.transforms[0].header.frame_id = odom_frame_id_;
513  }
514 
516 } // namespace ackermann_steering_controller
void init(const ros::Time &time)
Initialize the odometry.
Definition: odometry.cpp:68
double getX() const
x position getter
Definition: odometry.h:111
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
uint32_t getNumPublishers() const
#define ROS_INFO_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_THROTTLE_NAMED(period, name, args)
PLUGINLIB_EXPORT_CLASS(diff_drive_controller::DiffDriveController, controller_interface::ControllerBase)
void setWheelParams(double wheel_reparation_h, double wheel_radius)
Sets the wheel parameters: radius and separation.
Definition: odometry.cpp:126
void writeFromNonRT(const T &data)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Type const & getType() const
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string rear_wheel_name, const std::string front_steer_name, bool lookup_wheel_separation_h, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double wheel_separation_h_multiplier_
Wheel separation and radius calibration multipliers:
static double euclideanOfVectors(const urdf::Vector3 &vec1, const urdf::Vector3 &vec2)
bool getParam(const std::string &key, std::string &s) const
std::string odom_frame_id_
Frame to use for odometry and odom tf:
void updateOpenLoop(double linear, double angular, const ros::Time &time)
Updates the odometry class with latest velocity command.
Definition: odometry.cpp:114
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
double getLinear() const
linear velocity getter
Definition: odometry.h:129
double getY() const
y position getter
Definition: odometry.h:120
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
bool hasParam(const std::string &key) const
double getHeading() const
heading getter
Definition: odometry.h:102
static bool isCylinder(const urdf::LinkConstSharedPtr &link)
double wheel_separation_h_
Wheel separation, wrt the midpoint of the wheel width:
hardware_interface::JointHandle rear_wheel_joint_
Hardware handles:
double getAngular() const
angular velocity getter
Definition: odometry.h:138
void setCommand(double command)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
#define ROS_INFO_STREAM(args)
const std::string & getNamespace() const
#define ROS_ERROR_NAMED(name,...)
static Time now()
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
static bool getWheelRadius(const urdf::LinkConstSharedPtr &wheel_link, double &wheel_radius)
#define ROS_ERROR(...)
double limit(double &v, double v0, double v1, double dt)
double wheel_radius_
Wheel radius (assuming it&#39;s the same for the left and right wheels):
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
Definition: odometry.cpp:132
bool update(double rear_wheel_pos, double front_steer_pos, const ros::Time &time)
Updates the odometry class with latest wheels position.
Definition: odometry.cpp:75


ackermann_steering_controller
Author(s): Masaru Morita
autogenerated on Fri Feb 3 2023 03:19:04