four_wheel_steering_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Irstea
5  * Copyright (c) 2013, PAL Robotics, S.L.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Irstea nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <cmath>
38 #include <tf/transform_datatypes.h>
40 
42 
44  : command_struct_twist_()
45  , command_struct_four_wheel_steering_()
46  , track_(0.0)
47  , wheel_steering_y_offset_(0.0)
48  , wheel_radius_(0.0)
49  , wheel_base_(0.0)
50  , cmd_vel_timeout_(0.5)
51  , base_frame_id_("base_link")
52  , enable_odom_tf_(true)
53  , enable_twist_cmd_(false)
54  {
55  }
56 
58  ros::NodeHandle& root_nh,
59  ros::NodeHandle &controller_nh)
60  {
61  const std::string complete_ns = controller_nh.getNamespace();
62  std::size_t id = complete_ns.find_last_of("/");
63  name_ = complete_ns.substr(id + 1);
64 
65  // Get joint names from the parameter server
66  std::vector<std::string> front_wheel_names, rear_wheel_names;
67  if (!getWheelNames(controller_nh, "front_wheel", front_wheel_names) ||
68  !getWheelNames(controller_nh, "rear_wheel", rear_wheel_names))
69  {
70  return false;
71  }
72 
73  if (front_wheel_names.size() != rear_wheel_names.size())
74  {
76  "#front wheels (" << front_wheel_names.size() << ") != " <<
77  "#rear wheels (" << rear_wheel_names.size() << ").");
78  return false;
79  }
80  else if (front_wheel_names.size() != 2)
81  {
83  "#two wheels by axle (left and right) is needed; now : "<<front_wheel_names.size()<<" .");
84  return false;
85  }
86  else
87  {
88  front_wheel_joints_.resize(front_wheel_names.size());
89  rear_wheel_joints_.resize(front_wheel_names.size());
90  }
91 
92  // Get steering joint names from the parameter server
93  std::vector<std::string> front_steering_names, rear_steering_names;
94  if (!getWheelNames(controller_nh, "front_steering", front_steering_names) ||
95  !getWheelNames(controller_nh, "rear_steering", rear_steering_names))
96  {
97  return false;
98  }
99 
100  if (front_steering_names.size() != rear_steering_names.size())
101  {
103  "#left steerings (" << front_steering_names.size() << ") != " <<
104  "#right steerings (" << rear_steering_names.size() << ").");
105  return false;
106  }
107  else if (front_steering_names.size() != 2)
108  {
110  "#two steering by axle (left and right) is needed; now : "<<front_steering_names.size()<<" .");
111  return false;
112  }
113  else
114  {
115  front_steering_joints_.resize(front_steering_names.size());
116  rear_steering_joints_.resize(front_steering_names.size());
117  }
118 
119  // Odometry related:
120  double publish_rate;
121  controller_nh.param("publish_rate", publish_rate, 50.0);
122  ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
123  << publish_rate << "Hz.");
124  publish_period_ = ros::Duration(1.0 / publish_rate);
125 
126  controller_nh.param("open_loop", open_loop_, open_loop_);
127 
128  int velocity_rolling_window_size = 10;
129  controller_nh.param("velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
130  ROS_INFO_STREAM_NAMED(name_, "Velocity rolling window size of "
131  << velocity_rolling_window_size << ".");
132 
133  odometry_.setVelocityRollingWindowSize(velocity_rolling_window_size);
134 
135  // Twist command related:
136  controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
137  ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
138  << cmd_vel_timeout_ << "s.");
139 
140  controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
141  ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
142 
143  controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
144  ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
145 
146  // Velocity and acceleration limits:
147  controller_nh.param("linear/x/has_velocity_limits" , limiter_lin_.has_velocity_limits , limiter_lin_.has_velocity_limits );
148  controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
149  controller_nh.param("linear/x/max_velocity" , limiter_lin_.max_velocity , limiter_lin_.max_velocity );
150  controller_nh.param("linear/x/min_velocity" , limiter_lin_.min_velocity , -limiter_lin_.max_velocity );
151  controller_nh.param("linear/x/max_acceleration" , limiter_lin_.max_acceleration , limiter_lin_.max_acceleration );
152  controller_nh.param("linear/x/min_acceleration" , limiter_lin_.min_acceleration , -limiter_lin_.max_acceleration );
153 
154  controller_nh.param("angular/z/has_velocity_limits" , limiter_ang_.has_velocity_limits , limiter_ang_.has_velocity_limits );
155  controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
156  controller_nh.param("angular/z/max_velocity" , limiter_ang_.max_velocity , limiter_ang_.max_velocity );
157  controller_nh.param("angular/z/min_velocity" , limiter_ang_.min_velocity , -limiter_ang_.max_velocity );
158  controller_nh.param("angular/z/max_acceleration" , limiter_ang_.max_acceleration , limiter_ang_.max_acceleration );
159  controller_nh.param("angular/z/min_acceleration" , limiter_ang_.min_acceleration , -limiter_ang_.max_acceleration );
160 
161  // If either parameter is not available, we need to look up the value in the URDF
162  bool lookup_track = !controller_nh.getParam("track", track_);
163  bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheel_radius_);
164  bool lookup_wheel_base = !controller_nh.getParam("wheel_base", wheel_base_);
165 
167  if(lookup_track)
168  if(!uvk.getDistanceBetweenJoints(front_wheel_names[0], front_wheel_names[1], track_))
169  return false;
170  else
171  controller_nh.setParam("track",track_);
172 
173  if(!uvk.getDistanceBetweenJoints(front_steering_names[0], front_wheel_names[0], wheel_steering_y_offset_))
174  return false;
175  else
176  controller_nh.setParam("wheel_steering_y_offset",wheel_steering_y_offset_);
177 
178  if(lookup_wheel_radius)
179  if(!uvk.getJointRadius(front_wheel_names[0], wheel_radius_))
180  return false;
181  else
182  controller_nh.setParam("wheel_radius",wheel_radius_);
183 
184  if(lookup_wheel_base)
185  if(!uvk.getDistanceBetweenJoints(front_wheel_names[0], rear_wheel_names[0], wheel_base_))
186  return false;
187  else
188  controller_nh.setParam("wheel_base",wheel_base_);
189 
190  // Regardless of how we got the separation and radius, use them
191  // to set the odometry parameters
194  "Odometry params : track " << track_
195  << ", wheel radius " << wheel_radius_
196  << ", wheel base " << wheel_base_
197  << ", wheel steering offset " << wheel_steering_y_offset_);
198 
199  setOdomPubFields(root_nh, controller_nh);
200 
201 
204 
205  // Get the joint object to use in the realtime loop
206  for (size_t i = 0; i < front_wheel_joints_.size(); ++i)
207  {
209  "Adding front wheel with joint name: " << front_wheel_names[i]
210  << " and rear wheel with joint name: " << rear_wheel_names[i]);
211  front_wheel_joints_[i] = vel_joint_hw->getHandle(front_wheel_names[i]); // throws on failure
212  rear_wheel_joints_[i] = vel_joint_hw->getHandle(rear_wheel_names[i]); // throws on failure
213  }
214 
215  // Get the steering joint object to use in the realtime loop
216  for (size_t i = 0; i < front_steering_joints_.size(); ++i)
217  {
219  "Adding left steering with joint name: " << front_steering_names[i]
220  << " and right steering with joint name: " << rear_steering_names[i]);
221  front_steering_joints_[i] = pos_joint_hw->getHandle(front_steering_names[i]); // throws on failure
222  rear_steering_joints_[i] = pos_joint_hw->getHandle(rear_steering_names[i]); // throws on failure
223  }
224 
225  sub_command_ = controller_nh.subscribe("cmd_vel", 1, &FourWheelSteeringController::cmdVelCallback, this);
227 
228  return true;
229  }
230 
232  {
233  updateOdometry(time);
234  updateCommand(time, period);
235  }
236 
238  {
239  brake();
240 
241  // Register starting time used to keep fixed rate
243 
244  odometry_.init(time);
245  }
246 
248  {
249  brake();
250  }
251 
253  {
254  // COMPUTE AND PUBLISH ODOMETRY
255  const double fl_speed = front_wheel_joints_[0].getVelocity();
256  const double fr_speed = front_wheel_joints_[1].getVelocity();
257  const double rl_speed = rear_wheel_joints_[0].getVelocity();
258  const double rr_speed = rear_wheel_joints_[1].getVelocity();
259  if (std::isnan(fl_speed) || std::isnan(fr_speed)
260  || std::isnan(rl_speed) || std::isnan(rr_speed))
261  return;
262 
263  const double fl_steering = front_steering_joints_[0].getPosition();
264  const double fr_steering = front_steering_joints_[1].getPosition();
265  const double rl_steering = rear_steering_joints_[0].getPosition();
266  const double rr_steering = rear_steering_joints_[1].getPosition();
267  if (std::isnan(fl_steering) || std::isnan(fr_steering)
268  || std::isnan(rl_steering) || std::isnan(rr_steering))
269  return;
270  double front_steering_pos = 0.0;
271  if(fabs(fl_steering) > 0.001 || fabs(fr_steering) > 0.001)
272  {
273  front_steering_pos = atan(2*tan(fl_steering)*tan(fr_steering)/
274  (tan(fl_steering) + tan(fr_steering)));
275  }
276  double rear_steering_pos = 0.0;
277  if(fabs(rl_steering) > 0.001 || fabs(rr_steering) > 0.001)
278  {
279  rear_steering_pos = atan(2*tan(rl_steering)*tan(rr_steering)/
280  (tan(rl_steering) + tan(rr_steering)));
281  }
282 
283  ROS_DEBUG_STREAM_THROTTLE(1, "rl_steering "<<rl_steering<<" rr_steering "<<rr_steering<<" rear_steering_pos "<<rear_steering_pos);
284  // Estimate linear and angular velocity using joint information
285  odometry_.update(fl_speed, fr_speed, rl_speed, rr_speed,
286  front_steering_pos, rear_steering_pos, time);
287 
288  // Publish odometry message
290  {
292  // Compute and store orientation info
293  const geometry_msgs::Quaternion orientation(
295 
296  // Populate odom message and publish
297  if (odom_pub_->trylock())
298  {
299  odom_pub_->msg_.header.stamp = time;
300  odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
301  odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
302  odom_pub_->msg_.pose.pose.orientation = orientation;
303  odom_pub_->msg_.twist.twist.linear.x = odometry_.getLinearX();
304  odom_pub_->msg_.twist.twist.linear.y = odometry_.getLinearY();
305  odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular();
306  odom_pub_->unlockAndPublish();
307  }
308  if (odom_4ws_pub_->trylock())
309  {
310  odom_4ws_pub_->msg_.header.stamp = time;
311  odom_4ws_pub_->msg_.data.speed = odometry_.getLinear();
312  odom_4ws_pub_->msg_.data.acceleration = odometry_.getLinearAcceleration();
313  odom_4ws_pub_->msg_.data.jerk = odometry_.getLinearJerk();
314  odom_4ws_pub_->msg_.data.front_steering_angle = front_steering_pos;
315  odom_4ws_pub_->msg_.data.front_steering_angle_velocity = odometry_.getFrontSteerVel();
316  odom_4ws_pub_->msg_.data.rear_steering_angle = rear_steering_pos;
317  odom_4ws_pub_->msg_.data.rear_steering_angle_velocity = odometry_.getRearSteerVel();
318  odom_4ws_pub_->unlockAndPublish();
319  }
320 
321  // Publish tf /odom frame
322  if (enable_odom_tf_ && tf_odom_pub_->trylock())
323  {
324  geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0];
325  odom_frame.header.stamp = time;
326  odom_frame.transform.translation.x = odometry_.getX();
327  odom_frame.transform.translation.y = odometry_.getY();
328  odom_frame.transform.rotation = orientation;
329  tf_odom_pub_->unlockAndPublish();
330  }
331  }
332  }
333 
335  {
336  // Retreive current velocity command and time step:
337  Command* cmd;
338  CommandTwist curr_cmd_twist = *(command_twist_.readFromRT());
339  Command4ws curr_cmd_4ws = *(command_four_wheel_steering_.readFromRT());
340 
341  if(curr_cmd_4ws.stamp >= curr_cmd_twist.stamp)
342  {
343  cmd = &curr_cmd_4ws;
344  enable_twist_cmd_ = false;
345  }
346  else
347  {
348  cmd = &curr_cmd_twist;
349  enable_twist_cmd_ = true;
350  }
351 
352  const double dt = (time - cmd->stamp).toSec();
353  // Brake if cmd_vel has timeout:
354  if (dt > cmd_vel_timeout_)
355  {
356  curr_cmd_twist.lin_x = 0.0;
357  curr_cmd_twist.lin_y = 0.0;
358  curr_cmd_twist.ang = 0.0;
359  curr_cmd_4ws.lin = 0.0;
360  curr_cmd_4ws.front_steering = 0.0;
361  curr_cmd_4ws.rear_steering = 0.0;
362  }
363 
364  const double cmd_dt(period.toSec());
365 
366  const double angular_speed = odometry_.getAngular();
367  const double steering_track = track_-2*wheel_steering_y_offset_;
368 
369  ROS_DEBUG_STREAM("angular_speed "<<angular_speed<< " wheel_radius_ "<<wheel_radius_);
370  double vel_left_front = 0, vel_right_front = 0;
371  double vel_left_rear = 0, vel_right_rear = 0;
372  double front_left_steering = 0, front_right_steering = 0;
373  double rear_left_steering = 0, rear_right_steering = 0;
374 
375  if(enable_twist_cmd_ == true)
376  {
377  // Limit velocities and accelerations:
378  limiter_lin_.limit(curr_cmd_twist.lin_x, last0_cmd_.lin_x, last1_cmd_.lin_x, cmd_dt);
379  limiter_ang_.limit(curr_cmd_twist.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt);
381  last0_cmd_ = curr_cmd_twist;
382 
383  // Compute wheels velocities:
384  if(fabs(curr_cmd_twist.lin_x) > 0.001)
385  {
386  const double vel_steering_offset = (curr_cmd_twist.ang*wheel_steering_y_offset_)/wheel_radius_;
387  const double sign = copysign(1.0, curr_cmd_twist.lin_x);
388  vel_left_front = sign * std::hypot((curr_cmd_twist.lin_x - curr_cmd_twist.ang*steering_track/2),
389  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
390  - vel_steering_offset;
391  vel_right_front = sign * std::hypot((curr_cmd_twist.lin_x + curr_cmd_twist.ang*steering_track/2),
392  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
393  + vel_steering_offset;
394  vel_left_rear = sign * std::hypot((curr_cmd_twist.lin_x - curr_cmd_twist.ang*steering_track/2),
395  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
396  - vel_steering_offset;
397  vel_right_rear = sign * std::hypot((curr_cmd_twist.lin_x + curr_cmd_twist.ang*steering_track/2),
398  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
399  + vel_steering_offset;
400  }
401 
402  // Compute steering angles
403  if(fabs(2.0*curr_cmd_twist.lin_x) > fabs(curr_cmd_twist.ang*steering_track))
404  {
405  front_left_steering = atan(curr_cmd_twist.ang*wheel_base_ /
406  (2.0*curr_cmd_twist.lin_x - curr_cmd_twist.ang*steering_track));
407  front_right_steering = atan(curr_cmd_twist.ang*wheel_base_ /
408  (2.0*curr_cmd_twist.lin_x + curr_cmd_twist.ang*steering_track));
409  }
410  else if(fabs(curr_cmd_twist.lin_x) > 0.001)
411  {
412  front_left_steering = copysign(M_PI_2, curr_cmd_twist.ang);
413  front_right_steering = copysign(M_PI_2, curr_cmd_twist.ang);
414  }
415  rear_left_steering = -front_left_steering;
416  rear_right_steering = -front_right_steering;
417  }
418  else
419  {
420  // Limit velocities and accelerations:
421  limiter_lin_.limit(curr_cmd_4ws.lin, last0_cmd_.lin_x, last1_cmd_.lin_x, cmd_dt);
423  last0_cmd_.lin_x = curr_cmd_4ws.lin;
424  curr_cmd_4ws.front_steering = clamp(curr_cmd_4ws.front_steering, -M_PI_2, M_PI_2);
425  curr_cmd_4ws.rear_steering = clamp(curr_cmd_4ws.rear_steering, -M_PI_2, M_PI_2);
426 
427  // Compute steering angles
428  const double tan_front_steering = tan(curr_cmd_4ws.front_steering);
429  const double tan_rear_steering = tan(curr_cmd_4ws.rear_steering);
430 
431  const double steering_diff = steering_track*(tan_front_steering - tan_rear_steering)/2.0;
432  if(fabs(wheel_base_ - fabs(steering_diff)) > 0.001)
433  {
434  front_left_steering = atan(wheel_base_*tan_front_steering/(wheel_base_-steering_diff));
435  front_right_steering = atan(wheel_base_*tan_front_steering/(wheel_base_+steering_diff));
436  rear_left_steering = atan(wheel_base_*tan_rear_steering/(wheel_base_-steering_diff));
437  rear_right_steering = atan(wheel_base_*tan_rear_steering/(wheel_base_+steering_diff));
438  }
439 
440  // Compute wheels velocities:
441  if(fabs(curr_cmd_4ws.lin) > 0.001)
442  {
443  //Virutal front and rear wheelbase
444  // distance between the projection of the CIR on the wheelbase and the front axle
445  double l_front = 0;
446  if(fabs(tan(front_left_steering) - tan(front_right_steering)) > 0.01)
447  {
448  l_front = tan(front_right_steering) * tan(front_left_steering) * steering_track
449  / (tan(front_left_steering) - tan(front_right_steering));
450  }
451  // distance between the projection of the CIR on the wheelbase and the rear axle
452  double l_rear = 0;
453  if(fabs(tan(rear_left_steering) - tan(rear_right_steering)) > 0.01)
454  {
455  l_rear = tan(rear_right_steering) * tan(rear_left_steering) * steering_track
456  / (tan(rear_left_steering) - tan(rear_right_steering));
457  }
458 
459  const double angular_speed_cmd = curr_cmd_4ws.lin * (tan_front_steering-tan_rear_steering)/wheel_base_;
460  const double vel_steering_offset = (angular_speed_cmd*wheel_steering_y_offset_)/wheel_radius_;
461  const double sign = copysign(1.0, curr_cmd_4ws.lin);
462 
463  vel_left_front = sign * std::hypot((curr_cmd_4ws.lin - angular_speed_cmd*steering_track/2),
464  (l_front*angular_speed_cmd))/wheel_radius_
465  - vel_steering_offset;
466  vel_right_front = sign * std::hypot((curr_cmd_4ws.lin + angular_speed_cmd*steering_track/2),
467  (l_front*angular_speed_cmd))/wheel_radius_
468  + vel_steering_offset;
469  vel_left_rear = sign * std::hypot((curr_cmd_4ws.lin - angular_speed_cmd*steering_track/2),
470  (l_rear*angular_speed_cmd))/wheel_radius_
471  - vel_steering_offset;
472  vel_right_rear = sign * std::hypot((curr_cmd_4ws.lin + angular_speed_cmd*steering_track/2),
473  (l_rear*angular_speed_cmd))/wheel_radius_
474  + vel_steering_offset;
475  }
476  }
477 
478  ROS_DEBUG_STREAM_THROTTLE(1, "vel_left_rear "<<vel_left_rear<<" front_right_steering "<<front_right_steering);
479  // Set wheels velocities:
480  if(front_wheel_joints_.size() == 2 && rear_wheel_joints_.size() == 2)
481  {
482  front_wheel_joints_[0].setCommand(vel_left_front);
483  front_wheel_joints_[1].setCommand(vel_right_front);
484  rear_wheel_joints_[0].setCommand(vel_left_rear);
485  rear_wheel_joints_[1].setCommand(vel_right_rear);
486  }
487 
489  if(front_steering_joints_.size() == 2 && rear_steering_joints_.size() == 2)
490  {
491  front_steering_joints_[0].setCommand(front_left_steering);
492  front_steering_joints_[1].setCommand(front_right_steering);
493  rear_steering_joints_[0].setCommand(rear_left_steering);
494  rear_steering_joints_[1].setCommand(rear_right_steering);
495  }
496  }
497 
499  {
500  const double vel = 0.0;
501  for (size_t i = 0; i < front_wheel_joints_.size(); ++i)
502  {
503  front_wheel_joints_[i].setCommand(vel);
504  rear_wheel_joints_[i].setCommand(vel);
505  }
506 
507  const double pos = 0.0;
508  for (size_t i = 0; i < front_steering_joints_.size(); ++i)
509  {
510  front_steering_joints_[i].setCommand(pos);
511  rear_steering_joints_[i].setCommand(pos);
512  }
513  }
514 
515  void FourWheelSteeringController::cmdVelCallback(const geometry_msgs::Twist& command)
516  {
517  if (isRunning())
518  {
519  if(std::isnan(command.angular.z) || std::isnan(command.linear.x))
520  {
521  ROS_WARN("Received NaN in geometry_msgs::Twist. Ignoring command.");
522  return;
523  }
524  command_struct_twist_.ang = command.angular.z;
525  command_struct_twist_.lin_x = command.linear.x;
526  command_struct_twist_.lin_y = command.linear.y;
528  command_twist_.writeFromNonRT (command_struct_twist_);
530  "Added values to command. "
531  << "Ang: " << command_struct_twist_.ang << ", "
532  << "Lin x: " << command_struct_twist_.lin_x << ", "
533  << "Lin y: " << command_struct_twist_.lin_y << ", "
534  << "Stamp: " << command_struct_twist_.stamp);
535  }
536  else
537  {
538  ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
539  }
540  }
541 
542  void FourWheelSteeringController::cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering& command)
543  {
544  if (isRunning())
545  {
546  if(std::isnan(command.front_steering_angle) || std::isnan(command.rear_steering_angle)
547  || std::isnan(command.speed))
548  {
549  ROS_WARN("Received NaN in four_wheel_steering_msgs::FourWheelSteering. Ignoring command.");
550  return;
551  }
552  command_struct_four_wheel_steering_.front_steering = command.front_steering_angle;
553  command_struct_four_wheel_steering_.rear_steering = command.rear_steering_angle;
558  "Added values to command. "
559  << "Steering front : " << command_struct_four_wheel_steering_.front_steering << ", "
560  << "Steering rear : " << command_struct_four_wheel_steering_.rear_steering << ", "
561  << "Lin: " << command_struct_four_wheel_steering_.lin << ", "
563  }
564  else
565  {
566  ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
567  }
568  }
569 
571  const std::string& wheel_param,
572  std::vector<std::string>& wheel_names)
573  {
574  XmlRpc::XmlRpcValue wheel_list;
575  if (!controller_nh.getParam(wheel_param, wheel_list))
576  {
578  "Couldn't retrieve wheel param '" << wheel_param << "'.");
579  return false;
580  }
581 
582  if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
583  {
584  if (wheel_list.size() == 0)
585  {
587  "Wheel param '" << wheel_param << "' is an empty list");
588  return false;
589  }
590 
591  for (int i = 0; i < wheel_list.size(); ++i)
592  {
593  if (wheel_list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
594  {
596  "Wheel param '" << wheel_param << "' #" << i <<
597  " isn't a string.");
598  return false;
599  }
600  }
601 
602  wheel_names.resize(wheel_list.size());
603  for (int i = 0; i < wheel_list.size(); ++i)
604  {
605  wheel_names[i] = static_cast<std::string>(wheel_list[i]);
606  //ROS_INFO_STREAM("wheel name "<<i<<" " << wheel_names[i]);
607  }
608  }
609  else if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeString)
610  {
611  wheel_names.push_back(wheel_list);
612  }
613  else
614  {
616  "Wheel param '" << wheel_param <<
617  "' is neither a list of strings nor a string.");
618  return false;
619  }
620  return true;
621  }
622 
624  {
625  // Get and check params for covariances
626  XmlRpc::XmlRpcValue pose_cov_list;
627  controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
629  ROS_ASSERT(pose_cov_list.size() == 6);
630  for (int i = 0; i < pose_cov_list.size(); ++i)
631  ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
632 
633  XmlRpc::XmlRpcValue twist_cov_list;
634  controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
636  ROS_ASSERT(twist_cov_list.size() == 6);
637  for (int i = 0; i < twist_cov_list.size(); ++i)
638  ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
639 
640  // Setup odometry realtime publisher + odom message constant fields
641  odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
642  odom_pub_->msg_.header.frame_id = "odom";
643  odom_pub_->msg_.child_frame_id = base_frame_id_;
644  odom_pub_->msg_.pose.pose.position.z = 0;
645  odom_pub_->msg_.pose.covariance = {
646  static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
647  0., static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
648  0., 0., static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
649  0., 0., 0., static_cast<double>(pose_cov_list[3]), 0., 0.,
650  0., 0., 0., 0., static_cast<double>(pose_cov_list[4]), 0.,
651  0., 0., 0., 0., 0., static_cast<double>(pose_cov_list[5]) };
652  odom_pub_->msg_.twist.twist.linear.y = 0;
653  odom_pub_->msg_.twist.twist.linear.z = 0;
654  odom_pub_->msg_.twist.twist.angular.x = 0;
655  odom_pub_->msg_.twist.twist.angular.y = 0;
656  odom_pub_->msg_.twist.covariance = {
657  static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
658  0., static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
659  0., 0., static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
660  0., 0., 0., static_cast<double>(twist_cov_list[3]), 0., 0.,
661  0., 0., 0., 0., static_cast<double>(twist_cov_list[4]), 0.,
662  0., 0., 0., 0., 0., static_cast<double>(twist_cov_list[5]) };
664  odom_4ws_pub_->msg_.header.frame_id = "odom";
665 
666  tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
667  tf_odom_pub_->msg_.transforms.resize(1);
668  tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
669  tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_;
670  tf_odom_pub_->msg_.transforms[0].header.frame_id = "odom";
671  }
672 
673 } // namespace four_wheel_steering_controller
void setVelocityRollingWindowSize(size_t velocity_rolling_window_size)
Velocity rolling window size setter.
Definition: odometry.cpp:131
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
void updateCommand(const ros::Time &time, const ros::Duration &period)
Compute and publish command.
std::vector< hardware_interface::JointHandle > front_steering_joints_
std::vector< hardware_interface::JointHandle > rear_wheel_joints_
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
string cmd
double getLinearX() const
linear velocity getter along X on the robot base link frame
Definition: odometry.h:128
void updateOdometry(const ros::Time &time)
Update and publish odometry.
double getLinearAcceleration() const
linear acceleration getter
Definition: odometry.h:155
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
std::vector< hardware_interface::JointHandle > rear_steering_joints_
void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering &command)
Velocity and steering command callback.
#define ROS_INFO_STREAM_NAMED(name, args)
bool enable_twist_cmd_
Whether the control is make with four_wheel_steering msg or twist msg:
#define ROS_WARN(...)
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
double getFrontSteerVel() const
front steering velocity getter
Definition: odometry.h:173
double limit(double &v, double v0, double v1, double dt)
Limit the velocity and acceleration.
double wheel_radius_
Wheel radius (assuming it&#39;s the same for the left and right wheels):
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
bool update(const double &fl_speed, const double &fr_speed, const double &rl_speed, const double &rr_speed, double front_steering, double rear_steering, const ros::Time &time)
Updates the odometry class with latest wheels and steerings position.
Definition: odometry.cpp:72
std::vector< hardware_interface::JointHandle > front_wheel_joints_
Hardware handles:
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.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Type const & getType() const
double getAngular() const
angular velocity getter
Definition: odometry.h:146
double getX() const
x position getter
Definition: odometry.h:100
double getRearSteerVel() const
rear steering velocity getter
Definition: odometry.h:182
bool getParam(const std::string &key, std::string &s) const
std::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
double getY() const
y position getter
Definition: odometry.h:109
void setWheelParams(double steering_track, double wheel_steering_y_offset, double wheel_radius, double wheel_base)
Sets the wheel parameters: radius and separation.
Definition: odometry.cpp:123
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
#define ROS_DEBUG_STREAM(args)
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
bool getJointRadius(const std::string &joint_name, double &radius)
JointHandle getHandle(const std::string &name)
double getHeading() const
heading getter
Definition: odometry.h:91
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
const std::string & getNamespace() const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
double getLinearY() const
linear velocity getter along Y on the robot base link frame
Definition: odometry.h:137
#define ROS_ERROR_NAMED(name,...)
static Time now()
bool getDistanceBetweenJoints(const std::string &first_joint_name, const std::string &second_joint_name, double &distance)
double getLinear() const
linear velocity getter norm
Definition: odometry.h:119
#define ROS_ASSERT(cond)
void init(const ros::Time &time)
Initialize the odometry.
Definition: odometry.cpp:65
double track_
Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel w...
double wheel_base_
Wheel base (distance between front and rear wheel):
T clamp(T x, T min, T max)
Definition: speed_limiter.h:46
double getLinearJerk() const
linear jerk getter
Definition: odometry.h:164
realtime_tools::RealtimeBuffer< Command4ws > command_four_wheel_steering_
FourWheelSteering command related:


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri Feb 3 2023 03:19:10