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>
39 #include <tf/transform_datatypes.h>
41 
43 
45  : command_struct_twist_()
46  , command_struct_four_wheel_steering_()
47  , track_(0.0)
48  , wheel_steering_y_offset_(0.0)
49  , wheel_radius_(0.0)
50  , wheel_base_(0.0)
51  , cmd_vel_timeout_(0.5)
52  , base_frame_id_("base_link")
53  , enable_odom_tf_(true)
54  , enable_twist_cmd_(false)
55  {
56  }
57 
58  bool FourWheelSteeringController::init(hardware_interface::RobotHW *robot_hw,
59  ros::NodeHandle& root_nh,
60  ros::NodeHandle &controller_nh)
61  {
62  const std::string complete_ns = controller_nh.getNamespace();
63  std::size_t id = complete_ns.find_last_of("/");
64  name_ = complete_ns.substr(id + 1);
65 
66  // Get joint names from the parameter server
67  std::vector<std::string> front_wheel_names, rear_wheel_names;
68  if (!getWheelNames(controller_nh, "front_wheel", front_wheel_names) ||
69  !getWheelNames(controller_nh, "rear_wheel", rear_wheel_names))
70  {
71  return false;
72  }
73 
74  if (front_wheel_names.size() != rear_wheel_names.size())
75  {
77  "#front wheels (" << front_wheel_names.size() << ") != " <<
78  "#rear wheels (" << rear_wheel_names.size() << ").");
79  return false;
80  }
81  else if (front_wheel_names.size() != 2)
82  {
84  "#two wheels by axle (left and right) is needed; now : "<<front_wheel_names.size()<<" .");
85  return false;
86  }
87  else
88  {
89  front_wheel_joints_.resize(front_wheel_names.size());
90  rear_wheel_joints_.resize(front_wheel_names.size());
91  }
92 
93  // Get steering joint names from the parameter server
94  std::vector<std::string> front_steering_names, rear_steering_names;
95  if (!getWheelNames(controller_nh, "front_steering", front_steering_names) ||
96  !getWheelNames(controller_nh, "rear_steering", rear_steering_names))
97  {
98  return false;
99  }
100 
101  if (front_steering_names.size() != rear_steering_names.size())
102  {
104  "#left steerings (" << front_steering_names.size() << ") != " <<
105  "#right steerings (" << rear_steering_names.size() << ").");
106  return false;
107  }
108  else if (front_steering_names.size() != 2)
109  {
111  "#two steering by axle (left and right) is needed; now : "<<front_steering_names.size()<<" .");
112  return false;
113  }
114  else
115  {
116  front_steering_joints_.resize(front_steering_names.size());
117  rear_steering_joints_.resize(front_steering_names.size());
118  }
119 
120  // Odometry related:
121  double publish_rate;
122  controller_nh.param("publish_rate", publish_rate, 50.0);
123  ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at "
124  << publish_rate << "Hz.");
125  publish_period_ = ros::Duration(1.0 / publish_rate);
126 
127  controller_nh.param("open_loop", open_loop_, open_loop_);
128 
129  int velocity_rolling_window_size = 10;
130  controller_nh.param("velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size);
131  ROS_INFO_STREAM_NAMED(name_, "Velocity rolling window size of "
132  << velocity_rolling_window_size << ".");
133 
134  odometry_.setVelocityRollingWindowSize(velocity_rolling_window_size);
135 
136  // Twist command related:
137  controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_);
138  ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than "
139  << cmd_vel_timeout_ << "s.");
140 
141  controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_);
142  ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_);
143 
144  controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_);
145  ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled"));
146 
147  // Velocity and acceleration limits:
148  controller_nh.param("linear/x/has_velocity_limits" , limiter_lin_.has_velocity_limits , limiter_lin_.has_velocity_limits );
149  controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits);
150  controller_nh.param("linear/x/max_velocity" , limiter_lin_.max_velocity , limiter_lin_.max_velocity );
151  controller_nh.param("linear/x/min_velocity" , limiter_lin_.min_velocity , -limiter_lin_.max_velocity );
152  controller_nh.param("linear/x/max_acceleration" , limiter_lin_.max_acceleration , limiter_lin_.max_acceleration );
153  controller_nh.param("linear/x/min_acceleration" , limiter_lin_.min_acceleration , -limiter_lin_.max_acceleration );
154 
155  controller_nh.param("angular/z/has_velocity_limits" , limiter_ang_.has_velocity_limits , limiter_ang_.has_velocity_limits );
156  controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits);
157  controller_nh.param("angular/z/max_velocity" , limiter_ang_.max_velocity , limiter_ang_.max_velocity );
158  controller_nh.param("angular/z/min_velocity" , limiter_ang_.min_velocity , -limiter_ang_.max_velocity );
159  controller_nh.param("angular/z/max_acceleration" , limiter_ang_.max_acceleration , limiter_ang_.max_acceleration );
160  controller_nh.param("angular/z/min_acceleration" , limiter_ang_.min_acceleration , -limiter_ang_.max_acceleration );
161 
162  // If either parameter is not available, we need to look up the value in the URDF
163  bool lookup_track = !controller_nh.getParam("track", track_);
164  bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheel_radius_);
165  bool lookup_wheel_base = !controller_nh.getParam("wheel_base", wheel_base_);
166 
167  urdf_geometry_parser::UrdfGeometryParser uvk(root_nh, base_frame_id_);
168  if(lookup_track)
169  if(!uvk.getDistanceBetweenJoints(front_wheel_names[0], front_wheel_names[1], track_))
170  return false;
171  else
172  controller_nh.setParam("track",track_);
173 
174  if(!uvk.getDistanceBetweenJoints(front_steering_names[0], front_wheel_names[0], wheel_steering_y_offset_))
175  return false;
176  else
177  controller_nh.setParam("wheel_steering_y_offset",wheel_steering_y_offset_);
178 
179  if(lookup_wheel_radius)
180  if(!uvk.getJointRadius(front_wheel_names[0], wheel_radius_))
181  return false;
182  else
183  controller_nh.setParam("wheel_radius",wheel_radius_);
184 
185  if(lookup_wheel_base)
186  if(!uvk.getDistanceBetweenJoints(front_wheel_names[0], rear_wheel_names[0], wheel_base_))
187  return false;
188  else
189  controller_nh.setParam("wheel_base",wheel_base_);
190 
191  // Regardless of how we got the separation and radius, use them
192  // to set the odometry parameters
193  odometry_.setWheelParams(track_-2*wheel_steering_y_offset_, wheel_steering_y_offset_, wheel_radius_, wheel_base_);
194  ROS_INFO_STREAM_NAMED(name_,
195  "Odometry params : track " << track_
196  << ", wheel radius " << wheel_radius_
197  << ", wheel base " << wheel_base_
198  << ", wheel steering offset " << wheel_steering_y_offset_);
199 
200  setOdomPubFields(root_nh, controller_nh);
201 
202 
205 
206  // Get the joint object to use in the realtime loop
207  for (size_t i = 0; i < front_wheel_joints_.size(); ++i)
208  {
209  ROS_INFO_STREAM_NAMED(name_,
210  "Adding front wheel with joint name: " << front_wheel_names[i]
211  << " and rear wheel with joint name: " << rear_wheel_names[i]);
212  front_wheel_joints_[i] = vel_joint_hw->getHandle(front_wheel_names[i]); // throws on failure
213  rear_wheel_joints_[i] = vel_joint_hw->getHandle(rear_wheel_names[i]); // throws on failure
214  }
215 
216  // Get the steering joint object to use in the realtime loop
217  for (size_t i = 0; i < front_steering_joints_.size(); ++i)
218  {
219  ROS_INFO_STREAM_NAMED(name_,
220  "Adding left steering with joint name: " << front_steering_names[i]
221  << " and right steering with joint name: " << rear_steering_names[i]);
222  front_steering_joints_[i] = pos_joint_hw->getHandle(front_steering_names[i]); // throws on failure
223  rear_steering_joints_[i] = pos_joint_hw->getHandle(rear_steering_names[i]); // throws on failure
224  }
225 
226  sub_command_ = controller_nh.subscribe("cmd_vel", 1, &FourWheelSteeringController::cmdVelCallback, this);
227  sub_command_four_wheel_steering_ = controller_nh.subscribe("cmd_four_wheel_steering", 1, &FourWheelSteeringController::cmdFourWheelSteeringCallback, this);
228 
229  return true;
230  }
231 
232  void FourWheelSteeringController::update(const ros::Time& time, const ros::Duration& period)
233  {
234  updateOdometry(time);
235  updateCommand(time, period);
236  }
237 
238  void FourWheelSteeringController::starting(const ros::Time& time)
239  {
240  brake();
241 
242  // Register starting time used to keep fixed rate
243  last_state_publish_time_ = time;
244 
245  odometry_.init(time);
246  }
247 
248  void FourWheelSteeringController::stopping(const ros::Time& /*time*/)
249  {
250  brake();
251  }
252 
253  void FourWheelSteeringController::updateOdometry(const ros::Time& time)
254  {
255  // COMPUTE AND PUBLISH ODOMETRY
256  const double fl_speed = front_wheel_joints_[0].getVelocity();
257  const double fr_speed = front_wheel_joints_[1].getVelocity();
258  const double rl_speed = rear_wheel_joints_[0].getVelocity();
259  const double rr_speed = rear_wheel_joints_[1].getVelocity();
260  if (std::isnan(fl_speed) || std::isnan(fr_speed)
261  || std::isnan(rl_speed) || std::isnan(rr_speed))
262  return;
263 
264  const double fl_steering = front_steering_joints_[0].getPosition();
265  const double fr_steering = front_steering_joints_[1].getPosition();
266  const double rl_steering = rear_steering_joints_[0].getPosition();
267  const double rr_steering = rear_steering_joints_[1].getPosition();
268  if (std::isnan(fl_steering) || std::isnan(fr_steering)
269  || std::isnan(rl_steering) || std::isnan(rr_steering))
270  return;
271  double front_steering_pos = 0.0;
272  if(fabs(fl_steering) > 0.001 || fabs(fr_steering) > 0.001)
273  {
274  front_steering_pos = atan(2*tan(fl_steering)*tan(fr_steering)/
275  (tan(fl_steering) + tan(fr_steering)));
276  }
277  double rear_steering_pos = 0.0;
278  if(fabs(rl_steering) > 0.001 || fabs(rr_steering) > 0.001)
279  {
280  rear_steering_pos = atan(2*tan(rl_steering)*tan(rr_steering)/
281  (tan(rl_steering) + tan(rr_steering)));
282  }
283 
284  ROS_DEBUG_STREAM_THROTTLE(1, "rl_steering "<<rl_steering<<" rr_steering "<<rr_steering<<" rear_steering_pos "<<rear_steering_pos);
285  // Estimate linear and angular velocity using joint information
286  odometry_.update(fl_speed, fr_speed, rl_speed, rr_speed,
287  front_steering_pos, rear_steering_pos, time);
288 
289  // Publish odometry message
290  if (last_state_publish_time_ + publish_period_ < time)
291  {
292  last_state_publish_time_ += publish_period_;
293  // Compute and store orientation info
294  const geometry_msgs::Quaternion orientation(
295  tf::createQuaternionMsgFromYaw(odometry_.getHeading()));
296 
297  // Populate odom message and publish
298  if (odom_pub_->trylock())
299  {
300  odom_pub_->msg_.header.stamp = time;
301  odom_pub_->msg_.pose.pose.position.x = odometry_.getX();
302  odom_pub_->msg_.pose.pose.position.y = odometry_.getY();
303  odom_pub_->msg_.pose.pose.orientation = orientation;
304  odom_pub_->msg_.twist.twist.linear.x = odometry_.getLinearX();
305  odom_pub_->msg_.twist.twist.linear.y = odometry_.getLinearY();
306  odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular();
307  odom_pub_->unlockAndPublish();
308  }
309  if (odom_4ws_pub_->trylock())
310  {
311  odom_4ws_pub_->msg_.header.stamp = time;
312  odom_4ws_pub_->msg_.data.speed = odometry_.getLinear();
313  odom_4ws_pub_->msg_.data.acceleration = odometry_.getLinearAcceleration();
314  odom_4ws_pub_->msg_.data.jerk = odometry_.getLinearJerk();
315  odom_4ws_pub_->msg_.data.front_steering_angle = front_steering_pos;
316  odom_4ws_pub_->msg_.data.front_steering_angle_velocity = odometry_.getFrontSteerVel();
317  odom_4ws_pub_->msg_.data.rear_steering_angle = rear_steering_pos;
318  odom_4ws_pub_->msg_.data.rear_steering_angle_velocity = odometry_.getRearSteerVel();
319  odom_4ws_pub_->unlockAndPublish();
320  }
321 
322  // Publish tf /odom frame
323  if (enable_odom_tf_ && tf_odom_pub_->trylock())
324  {
325  geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0];
326  odom_frame.header.stamp = time;
327  odom_frame.transform.translation.x = odometry_.getX();
328  odom_frame.transform.translation.y = odometry_.getY();
329  odom_frame.transform.rotation = orientation;
330  tf_odom_pub_->unlockAndPublish();
331  }
332  }
333  }
334 
335  void FourWheelSteeringController::updateCommand(const ros::Time& time, const ros::Duration& period)
336  {
337  // Retreive current velocity command and time step:
338  Command* cmd;
339  CommandTwist curr_cmd_twist = *(command_twist_.readFromRT());
340  Command4ws curr_cmd_4ws = *(command_four_wheel_steering_.readFromRT());
341 
342  if(curr_cmd_4ws.stamp >= curr_cmd_twist.stamp)
343  {
344  cmd = &curr_cmd_4ws;
345  enable_twist_cmd_ = false;
346  }
347  else
348  {
349  cmd = &curr_cmd_twist;
350  enable_twist_cmd_ = true;
351  }
352 
353  const double dt = (time - cmd->stamp).toSec();
354  // Brake if cmd_vel has timeout:
355  if (dt > cmd_vel_timeout_)
356  {
357  curr_cmd_twist.lin_x = 0.0;
358  curr_cmd_twist.lin_y = 0.0;
359  curr_cmd_twist.ang = 0.0;
360  curr_cmd_4ws.lin = 0.0;
361  curr_cmd_4ws.front_steering = 0.0;
362  curr_cmd_4ws.rear_steering = 0.0;
363  }
364 
365  const double cmd_dt(period.toSec());
366 
367  const double angular_speed = odometry_.getAngular();
368  const double steering_track = track_-2*wheel_steering_y_offset_;
369 
370  ROS_DEBUG_STREAM("angular_speed "<<angular_speed<< " wheel_radius_ "<<wheel_radius_);
371  double vel_left_front = 0, vel_right_front = 0;
372  double vel_left_rear = 0, vel_right_rear = 0;
373  double front_left_steering = 0, front_right_steering = 0;
374  double rear_left_steering = 0, rear_right_steering = 0;
375 
376  if(enable_twist_cmd_ == true)
377  {
378  // Limit velocities and accelerations:
379  limiter_lin_.limit(curr_cmd_twist.lin_x, last0_cmd_.lin_x, last1_cmd_.lin_x, cmd_dt);
380  limiter_ang_.limit(curr_cmd_twist.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt);
381  last1_cmd_ = last0_cmd_;
382  last0_cmd_ = curr_cmd_twist;
383 
384  // Compute wheels velocities:
385  if(fabs(curr_cmd_twist.lin_x) > 0.001)
386  {
387  const double vel_steering_offset = (curr_cmd_twist.ang*wheel_steering_y_offset_)/wheel_radius_;
388  const double sign = copysign(1.0, curr_cmd_twist.lin_x);
389  vel_left_front = sign * std::hypot((curr_cmd_twist.lin_x - curr_cmd_twist.ang*steering_track/2),
390  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
391  - vel_steering_offset;
392  vel_right_front = sign * std::hypot((curr_cmd_twist.lin_x + curr_cmd_twist.ang*steering_track/2),
393  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
394  + vel_steering_offset;
395  vel_left_rear = sign * std::hypot((curr_cmd_twist.lin_x - curr_cmd_twist.ang*steering_track/2),
396  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
397  - vel_steering_offset;
398  vel_right_rear = sign * std::hypot((curr_cmd_twist.lin_x + curr_cmd_twist.ang*steering_track/2),
399  (wheel_base_*curr_cmd_twist.ang/2.0)) / wheel_radius_
400  + vel_steering_offset;
401  }
402 
403  // Compute steering angles
404  if(fabs(2.0*curr_cmd_twist.lin_x) > fabs(curr_cmd_twist.ang*steering_track))
405  {
406  front_left_steering = atan(curr_cmd_twist.ang*wheel_base_ /
407  (2.0*curr_cmd_twist.lin_x - curr_cmd_twist.ang*steering_track));
408  front_right_steering = atan(curr_cmd_twist.ang*wheel_base_ /
409  (2.0*curr_cmd_twist.lin_x + curr_cmd_twist.ang*steering_track));
410  }
411  else if(fabs(curr_cmd_twist.lin_x) > 0.001)
412  {
413  front_left_steering = copysign(M_PI_2, curr_cmd_twist.ang);
414  front_right_steering = copysign(M_PI_2, curr_cmd_twist.ang);
415  }
416  rear_left_steering = -front_left_steering;
417  rear_right_steering = -front_right_steering;
418  }
419  else
420  {
421  // Limit velocities and accelerations:
422  limiter_lin_.limit(curr_cmd_4ws.lin, last0_cmd_.lin_x, last1_cmd_.lin_x, cmd_dt);
423  last1_cmd_ = last0_cmd_;
424  last0_cmd_.lin_x = curr_cmd_4ws.lin;
425  curr_cmd_4ws.front_steering = clamp(curr_cmd_4ws.front_steering, -M_PI_2, M_PI_2);
426  curr_cmd_4ws.rear_steering = clamp(curr_cmd_4ws.rear_steering, -M_PI_2, M_PI_2);
427 
428  // Compute steering angles
429  const double tan_front_steering = tan(curr_cmd_4ws.front_steering);
430  const double tan_rear_steering = tan(curr_cmd_4ws.rear_steering);
431 
432  const double steering_diff = steering_track*(tan_front_steering - tan_rear_steering)/2.0;
433  if(fabs(wheel_base_ - fabs(steering_diff)) > 0.001)
434  {
435  front_left_steering = atan(wheel_base_*tan_front_steering/(wheel_base_-steering_diff));
436  front_right_steering = atan(wheel_base_*tan_front_steering/(wheel_base_+steering_diff));
437  rear_left_steering = atan(wheel_base_*tan_rear_steering/(wheel_base_-steering_diff));
438  rear_right_steering = atan(wheel_base_*tan_rear_steering/(wheel_base_+steering_diff));
439  }
440 
441  // Compute wheels velocities:
442  if(fabs(curr_cmd_4ws.lin) > 0.001)
443  {
444  //Virutal front and rear wheelbase
445  // distance between the projection of the CIR on the wheelbase and the front axle
446  double l_front = 0;
447  if(fabs(tan(front_left_steering) - tan(front_right_steering)) > 0.01)
448  {
449  l_front = tan(front_right_steering) * tan(front_left_steering) * steering_track
450  / (tan(front_left_steering) - tan(front_right_steering));
451  }
452  // distance between the projection of the CIR on the wheelbase and the rear axle
453  double l_rear = 0;
454  if(fabs(tan(rear_left_steering) - tan(rear_right_steering)) > 0.01)
455  {
456  l_rear = tan(rear_right_steering) * tan(rear_left_steering) * steering_track
457  / (tan(rear_left_steering) - tan(rear_right_steering));
458  }
459 
460  const double angular_speed_cmd = curr_cmd_4ws.lin * (tan_front_steering-tan_rear_steering)/wheel_base_;
461  const double vel_steering_offset = (angular_speed_cmd*wheel_steering_y_offset_)/wheel_radius_;
462  const double sign = copysign(1.0, curr_cmd_4ws.lin);
463 
464  vel_left_front = sign * std::hypot((curr_cmd_4ws.lin - angular_speed_cmd*steering_track/2),
465  (l_front*angular_speed_cmd))/wheel_radius_
466  - vel_steering_offset;
467  vel_right_front = sign * std::hypot((curr_cmd_4ws.lin + angular_speed_cmd*steering_track/2),
468  (l_front*angular_speed_cmd))/wheel_radius_
469  + vel_steering_offset;
470  vel_left_rear = sign * std::hypot((curr_cmd_4ws.lin - angular_speed_cmd*steering_track/2),
471  (l_rear*angular_speed_cmd))/wheel_radius_
472  - vel_steering_offset;
473  vel_right_rear = sign * std::hypot((curr_cmd_4ws.lin + angular_speed_cmd*steering_track/2),
474  (l_rear*angular_speed_cmd))/wheel_radius_
475  + vel_steering_offset;
476  }
477  }
478 
479  ROS_DEBUG_STREAM_THROTTLE(1, "vel_left_rear "<<vel_left_rear<<" front_right_steering "<<front_right_steering);
480  // Set wheels velocities:
481  if(front_wheel_joints_.size() == 2 && rear_wheel_joints_.size() == 2)
482  {
483  front_wheel_joints_[0].setCommand(vel_left_front);
484  front_wheel_joints_[1].setCommand(vel_right_front);
485  rear_wheel_joints_[0].setCommand(vel_left_rear);
486  rear_wheel_joints_[1].setCommand(vel_right_rear);
487  }
488 
490  if(front_steering_joints_.size() == 2 && rear_steering_joints_.size() == 2)
491  {
492  front_steering_joints_[0].setCommand(front_left_steering);
493  front_steering_joints_[1].setCommand(front_right_steering);
494  rear_steering_joints_[0].setCommand(rear_left_steering);
495  rear_steering_joints_[1].setCommand(rear_right_steering);
496  }
497  }
498 
499  void FourWheelSteeringController::brake()
500  {
501  const double vel = 0.0;
502  for (size_t i = 0; i < front_wheel_joints_.size(); ++i)
503  {
504  front_wheel_joints_[i].setCommand(vel);
505  rear_wheel_joints_[i].setCommand(vel);
506  }
507 
508  const double pos = 0.0;
509  for (size_t i = 0; i < front_steering_joints_.size(); ++i)
510  {
511  front_steering_joints_[i].setCommand(pos);
512  rear_steering_joints_[i].setCommand(pos);
513  }
514  }
515 
516  void FourWheelSteeringController::cmdVelCallback(const geometry_msgs::Twist& command)
517  {
518  if (isRunning())
519  {
520  if(std::isnan(command.angular.z) || std::isnan(command.linear.x))
521  {
522  ROS_WARN("Received NaN in geometry_msgs::Twist. Ignoring command.");
523  return;
524  }
525  command_struct_twist_.ang = command.angular.z;
526  command_struct_twist_.lin_x = command.linear.x;
527  command_struct_twist_.lin_y = command.linear.y;
528  command_struct_twist_.stamp = ros::Time::now();
529  command_twist_.writeFromNonRT (command_struct_twist_);
531  "Added values to command. "
532  << "Ang: " << command_struct_twist_.ang << ", "
533  << "Lin x: " << command_struct_twist_.lin_x << ", "
534  << "Lin y: " << command_struct_twist_.lin_y << ", "
535  << "Stamp: " << command_struct_twist_.stamp);
536  }
537  else
538  {
539  ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
540  }
541  }
542 
543  void FourWheelSteeringController::cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering& command)
544  {
545  if (isRunning())
546  {
547  if(std::isnan(command.front_steering_angle) || std::isnan(command.rear_steering_angle)
548  || std::isnan(command.speed))
549  {
550  ROS_WARN("Received NaN in four_wheel_steering_msgs::FourWheelSteering. Ignoring command.");
551  return;
552  }
553  command_struct_four_wheel_steering_.front_steering = command.front_steering_angle;
554  command_struct_four_wheel_steering_.rear_steering = command.rear_steering_angle;
555  command_struct_four_wheel_steering_.lin = command.speed;
556  command_struct_four_wheel_steering_.stamp = ros::Time::now();
557  command_four_wheel_steering_.writeFromNonRT (command_struct_four_wheel_steering_);
559  "Added values to command. "
560  << "Steering front : " << command_struct_four_wheel_steering_.front_steering << ", "
561  << "Steering rear : " << command_struct_four_wheel_steering_.rear_steering << ", "
562  << "Lin: " << command_struct_four_wheel_steering_.lin << ", "
563  << "Stamp: " << command_struct_four_wheel_steering_.stamp);
564  }
565  else
566  {
567  ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running.");
568  }
569  }
570 
571  bool FourWheelSteeringController::getWheelNames(ros::NodeHandle& controller_nh,
572  const std::string& wheel_param,
573  std::vector<std::string>& wheel_names)
574  {
575  XmlRpc::XmlRpcValue wheel_list;
576  if (!controller_nh.getParam(wheel_param, wheel_list))
577  {
579  "Couldn't retrieve wheel param '" << wheel_param << "'.");
580  return false;
581  }
582 
583  if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray)
584  {
585  if (wheel_list.size() == 0)
586  {
588  "Wheel param '" << wheel_param << "' is an empty list");
589  return false;
590  }
591 
592  for (int i = 0; i < wheel_list.size(); ++i)
593  {
594  if (wheel_list[i].getType() != XmlRpc::XmlRpcValue::TypeString)
595  {
597  "Wheel param '" << wheel_param << "' #" << i <<
598  " isn't a string.");
599  return false;
600  }
601  }
602 
603  wheel_names.resize(wheel_list.size());
604  for (int i = 0; i < wheel_list.size(); ++i)
605  {
606  wheel_names[i] = static_cast<std::string>(wheel_list[i]);
607  //ROS_INFO_STREAM("wheel name "<<i<<" " << wheel_names[i]);
608  }
609  }
610  else if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeString)
611  {
612  wheel_names.push_back(wheel_list);
613  }
614  else
615  {
617  "Wheel param '" << wheel_param <<
618  "' is neither a list of strings nor a string.");
619  return false;
620  }
621  return true;
622  }
623 
624  void FourWheelSteeringController::setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh)
625  {
626  // Get and check params for covariances
627  XmlRpc::XmlRpcValue pose_cov_list;
628  controller_nh.getParam("pose_covariance_diagonal", pose_cov_list);
630  ROS_ASSERT(pose_cov_list.size() == 6);
631  for (int i = 0; i < pose_cov_list.size(); ++i)
632  ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
633 
634  XmlRpc::XmlRpcValue twist_cov_list;
635  controller_nh.getParam("twist_covariance_diagonal", twist_cov_list);
637  ROS_ASSERT(twist_cov_list.size() == 6);
638  for (int i = 0; i < twist_cov_list.size(); ++i)
639  ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble);
640 
641  // Setup odometry realtime publisher + odom message constant fields
642  odom_pub_.reset(new realtime_tools::RealtimePublisher<nav_msgs::Odometry>(controller_nh, "odom", 100));
643  odom_pub_->msg_.header.frame_id = "odom";
644  odom_pub_->msg_.child_frame_id = base_frame_id_;
645  odom_pub_->msg_.pose.pose.position.z = 0;
646  odom_pub_->msg_.pose.covariance = {
647  static_cast<double>(pose_cov_list[0]), 0., 0., 0., 0., 0.,
648  0., static_cast<double>(pose_cov_list[1]), 0., 0., 0., 0.,
649  0., 0., static_cast<double>(pose_cov_list[2]), 0., 0., 0.,
650  0., 0., 0., static_cast<double>(pose_cov_list[3]), 0., 0.,
651  0., 0., 0., 0., static_cast<double>(pose_cov_list[4]), 0.,
652  0., 0., 0., 0., 0., static_cast<double>(pose_cov_list[5]) };
653  odom_pub_->msg_.twist.twist.linear.y = 0;
654  odom_pub_->msg_.twist.twist.linear.z = 0;
655  odom_pub_->msg_.twist.twist.angular.x = 0;
656  odom_pub_->msg_.twist.twist.angular.y = 0;
657  odom_pub_->msg_.twist.covariance = {
658  static_cast<double>(twist_cov_list[0]), 0., 0., 0., 0., 0.,
659  0., static_cast<double>(twist_cov_list[1]), 0., 0., 0., 0.,
660  0., 0., static_cast<double>(twist_cov_list[2]), 0., 0., 0.,
661  0., 0., 0., static_cast<double>(twist_cov_list[3]), 0., 0.,
662  0., 0., 0., 0., static_cast<double>(twist_cov_list[4]), 0.,
663  0., 0., 0., 0., 0., static_cast<double>(twist_cov_list[5]) };
664  odom_4ws_pub_.reset(new realtime_tools::RealtimePublisher<four_wheel_steering_msgs::FourWheelSteeringStamped>(controller_nh, "odom_steer", 100));
665  odom_4ws_pub_->msg_.header.frame_id = "odom";
666 
667  tf_odom_pub_.reset(new realtime_tools::RealtimePublisher<tf::tfMessage>(root_nh, "/tf", 100));
668  tf_odom_pub_->msg_.transforms.resize(1);
669  tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0;
670  tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_;
671  tf_odom_pub_->msg_.transforms[0].header.frame_id = "odom";
672  }
673 
674 } // namespace four_wheel_steering_controller
675 
XmlRpc::XmlRpcValue::size
int size() const
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
HardwareResourceManager< JointHandle, ClaimResources >::getHandle
JointHandle getHandle(const std::string &name)
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
hardware_interface::InterfaceManager::get
T * get()
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
urdf_geometry_parser::UrdfGeometryParser
command
ROSLIB_DECL std::string command(const std::string &cmd)
four_wheel_steering_controller.h
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
realtime_tools::RealtimePublisher
controller_interface::ControllerBase
hardware_interface::VelocityJointInterface
XmlRpc::XmlRpcValue::TypeDouble
TypeDouble
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
hardware_interface::RobotHW
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
XmlRpc::XmlRpcValue::TypeString
TypeString
urdf_geometry_parser.h
four_wheel_steering_controller::FourWheelSteeringController
Definition: four_wheel_steering_controller.h:96
ROS_WARN
#define ROS_WARN(...)
ROS_DEBUG_STREAM_THROTTLE
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
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())
XmlRpc::XmlRpcValue::getType
const Type & getType() const
four_wheel_steering_controller
Definition: four_wheel_steering_controller.h:52
XmlRpc::XmlRpcValue::TypeArray
TypeArray
ros::Time::init
static void init()
transform_datatypes.h
ros::Time
four_wheel_steering_controller::clamp
T clamp(T x, T min, T max)
Definition: speed_limiter.h:78
four_wheel_steering_controller::FourWheelSteeringController::FourWheelSteeringController
FourWheelSteeringController()
Definition: four_wheel_steering_controller.cpp:77
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
DurationBase< Duration >::toSec
double toSec() const
cmd
string cmd
hardware_interface::PositionJointInterface
ROS_ASSERT
#define ROS_ASSERT(cond)
tf::createQuaternionMsgFromYaw
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ros::Duration
XmlRpc::XmlRpcValue
ros::NodeHandle
ros::Time::now
static Time now()


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri May 24 2024 02:41:15