ackermann_steering_bot.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 // NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials
31 
32 #pragma once
33 
34 
35 // ROS
36 #include <ros/ros.h>
37 #include <std_msgs/Float64.h>
38 #include <std_srvs/Empty.h>
39 
40 // ros_control
41 #include <controller_manager/controller_manager.h>
46 
47 // NaN
48 #include <limits>
49 
50 // ostringstream
51 #include <sstream>
52 
56 };
57 
59 {
60 public:
62  : running_(true)
65  , ns_("ackermann_steering_bot_hw_sim/")
66  {
67  // Intialize raw data
68  this->cleanUp();
69  this->getJointNames(nh_);
71 
72  nh_.getParam(ns_ + "wheel_separation_w", wheel_separation_w_);
73  nh_.getParam(ns_ + "wheel_separation_h", wheel_separation_h_);
74  ROS_INFO_STREAM("wheel_separation_w in test ackermann_steering_bot= " << wheel_separation_w_);
75  ROS_INFO_STREAM("wheel_separation_h in test ackermann_steering_bot= " << wheel_separation_h_);
76  }
77 
78  ros::Time getTime() const {return ros::Time::now();}
79  ros::Duration getPeriod() const {return ros::Duration(0.01);}
80 
81  void read()
82  {
83  // Read the joint state of the robot into the hardware interface
84  std::ostringstream os;
85  if (running_)
86  {
87  // wheels
90  for (unsigned int i = 0; i < virtual_rear_wheel_jnt_vel_cmd_.size(); i++)
91  {
92  // Note that pos_[i] will be NaN for one more cycle after we start(),
93  // but that is consistent with the knowledge we have about the state
94  // of the robot.
97  }
98 
99  // steers
101  for (unsigned int i = 0; i < virtual_front_steer_jnt_pos_cmd_.size(); i++)
102  {
104  }
105 
106  // directly get from controller
107  os << rear_wheel_jnt_vel_cmd_ << ", ";
108  os << front_steer_jnt_pos_cmd_ << ", ";
109 
110  // convert to each joint velocity
111  //-- differential drive
112  for (unsigned int i = 0; i < virtual_rear_wheel_jnt_pos_.size(); i++)
113  {
114  os << virtual_rear_wheel_jnt_pos_[i] << ", ";
115  }
116 
117  //-- ackerman link
118  for (unsigned int i = 0; i < virtual_front_steer_jnt_pos_.size(); i++)
119  {
120  os << virtual_front_steer_jnt_pos_[i] << ", ";
121  }
122  }
123  else
124  {
125  // wheels
126  rear_wheel_jnt_pos_= std::numeric_limits<double>::quiet_NaN();
127  rear_wheel_jnt_vel_= std::numeric_limits<double>::quiet_NaN();
128  std::fill_n(virtual_rear_wheel_jnt_pos_.begin(), virtual_rear_wheel_jnt_pos_.size(), std::numeric_limits<double>::quiet_NaN());
129  std::fill_n(virtual_rear_wheel_jnt_vel_.begin(), virtual_rear_wheel_jnt_vel_.size(), std::numeric_limits<double>::quiet_NaN());
130  // steers
131  front_steer_jnt_pos_= std::numeric_limits<double>::quiet_NaN();
132  front_steer_jnt_vel_= std::numeric_limits<double>::quiet_NaN();
133  std::fill_n(virtual_front_steer_jnt_pos_.begin(), virtual_front_steer_jnt_pos_.size(), std::numeric_limits<double>::quiet_NaN());
134  std::fill_n(virtual_front_steer_jnt_vel_.begin(), virtual_front_steer_jnt_vel_.size(), std::numeric_limits<double>::quiet_NaN());
135 
136  // wheels
137  os << rear_wheel_jnt_pos_ << ", ";
138  os << rear_wheel_jnt_vel_ << ", ";
139  for (unsigned int i = 0; i < virtual_rear_wheel_jnt_pos_.size(); i++)
140  {
141  os << virtual_rear_wheel_jnt_pos_[i] << ", ";
142  }
143 
144  // steers
145  os << front_steer_jnt_pos_ << ", ";
146  os << front_steer_jnt_vel_ << ", ";
147  for (unsigned int i = 0; i < virtual_front_steer_jnt_pos_.size(); i++)
148  {
149  os << virtual_front_steer_jnt_pos_[i] << ", ";
150  }
151  }
152  ROS_INFO_STREAM("running_ = " << running_ << ". commands are " << os.str());
153  }
154 
155  void write()
156  {
157  // Write the commands to the joints
158  std::ostringstream os;
159  // directly get from controller
160  os << rear_wheel_jnt_vel_cmd_ << ", ";
161  os << front_steer_jnt_pos_cmd_ << ", ";
162 
163  // convert to each joint velocity
164  //-- differential drive
165  for (unsigned int i = 0; i < virtual_rear_wheel_jnt_vel_cmd_.size(); i++)
166  {
168  os << virtual_rear_wheel_jnt_vel_cmd_[i] << ", ";
169  }
170 
171  //-- ackerman link
172  const double h = wheel_separation_h_;
173  const double w = wheel_separation_w_;
174  virtual_front_steer_jnt_pos_cmd_[INDEX_RIGHT] = atan2(2*h*tan(front_steer_jnt_pos_cmd_), 2*h + w/2.0*tan(front_steer_jnt_pos_cmd_));
175  virtual_front_steer_jnt_pos_cmd_[INDEX_LEFT] = atan2(2*h*tan(front_steer_jnt_pos_cmd_), 2*h - w/2.0*tan(front_steer_jnt_pos_cmd_));
176 
177  for (unsigned int i = 0; i < virtual_front_steer_jnt_pos_cmd_.size(); i++)
178  {
179  os << virtual_front_steer_jnt_pos_cmd_[i] << ", ";
180  }
181 
182  if (rear_wheel_jnt_vel_cmd_ != 0.0 || front_steer_jnt_pos_cmd_ != 0.0)
183  {
184  ROS_INFO_STREAM("Commands for joints: " << os.str());
185  }
186  }
187 
188  bool startCallback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
189  {
190  ROS_INFO_STREAM("running_ = " << running_ << ".");
191  running_ = true;
192  return true;
193  }
194 
195  bool stopCallback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
196  {
197  ROS_INFO_STREAM("running_ = " << running_ << ".");
198  running_ = false;
199  return true;
200  }
201 
202 private:
203 
204  void cleanUp()
205  {
206  // wheel
207  //-- wheel joint names
208  rear_wheel_jnt_name_.empty();
210  //-- actual rear wheel joint
215  //-- virtual rear wheel joint
220  //-- virtual front wheel joint
225 
226  // steer
227  //-- steer joint names
228  front_steer_jnt_name_.empty();
230  //-- front steer joint
235  //-- virtual wheel joint
240  }
241 
243  {
244  this->getWheelJointNames(_nh);
245  this->getSteerJointNames(_nh);
246  }
247 
249  {
250  // wheel joint to get linear command
251  _nh.getParam(ns_ + "rear_wheel", rear_wheel_jnt_name_);
252 
253  // virtual wheel joint for gazebo con_rol
254  _nh.getParam(ns_ + "rear_wheels", virtual_rear_wheel_jnt_names_);
255  int dof = virtual_rear_wheel_jnt_names_.size();
256  virtual_rear_wheel_jnt_pos_.resize(dof);
257  virtual_rear_wheel_jnt_vel_.resize(dof);
258  virtual_rear_wheel_jnt_eff_.resize(dof);
260 
261  _nh.getParam(ns_ + "front_wheels", virtual_front_wheel_jnt_names_);
262  dof = virtual_front_wheel_jnt_names_.size();
263  virtual_front_wheel_jnt_pos_.resize(dof);
264  virtual_front_wheel_jnt_vel_.resize(dof);
265  virtual_front_wheel_jnt_eff_.resize(dof);
267  }
268 
270  {
271  // steer joint to get angular command
272  _nh.getParam(ns_ + "front_steer", front_steer_jnt_name_);
273 
274  // virtual steer joint for gazebo control
275  _nh.getParam(ns_ + "front_steers", virtual_front_steer_jnt_names_);
276 
277  const int dof = virtual_front_steer_jnt_names_.size();
278  virtual_front_steer_jnt_pos_.resize(dof);
279  virtual_front_steer_jnt_vel_.resize(dof);
280  virtual_front_steer_jnt_eff_.resize(dof);
282  }
283 
285  {
286  this->registerSteerInterface();
287  this->registerWheelInterface();
288 
289  // register mapped interface to ros_control
293  }
294 
296  {
297  // actual wheel joints
301 
302  // virtual rear wheel joints
303  for (int i = 0; i < virtual_rear_wheel_jnt_names_.size(); i++)
304  {
308  }
309  // virtual front wheel joints
310  for (int i = 0; i < virtual_front_wheel_jnt_names_.size(); i++)
311  {
315  }
316  }
317 
319  {
320  // actual steer joints
324 
325  // virtual steer joints
326  for (int i = 0; i < virtual_front_steer_jnt_names_.size(); i++)
327  {
331  }
332  }
333 
335  hardware_interface::JointStateInterface& _jnt_state_interface,
336  hardware_interface::JointCommandInterface& _jnt_cmd_interface,
337  const std::string _jnt_name, double& _jnt_pos, double& _jnt_vel, double& _jnt_eff, double& _jnt_cmd)
338  {
339  // register joint (both JointState and CommandJoint)
340  this->registerJointStateInterfaceHandle(_jnt_state_interface, _jnt_name,
341  _jnt_pos, _jnt_vel, _jnt_eff);
342  this->registerCommandJointInterfaceHandle(_jnt_state_interface, _jnt_cmd_interface,
343  _jnt_name, _jnt_cmd);
344  }
345 
347  hardware_interface::JointStateInterface& _jnt_state_interface,
348  const std::string _jnt_name, double& _jnt_pos, double& _jnt_vel, double& _jnt_eff)
349  {
350  hardware_interface::JointStateHandle state_handle(_jnt_name,
351  &_jnt_pos,
352  &_jnt_vel,
353  &_jnt_eff);
354  _jnt_state_interface.registerHandle(state_handle);
355 
356  ROS_INFO_STREAM("Registered joint '" << _jnt_name << " ' in the JointStateInterface");
357  }
358 
360  hardware_interface::JointStateInterface& _jnt_state_interface,
361  hardware_interface::JointCommandInterface& _jnt_cmd_interface,
362  const std::string _jnt_name, double& _jnt_cmd)
363  {
364  // joint command
365  hardware_interface::JointHandle _handle(_jnt_state_interface.getHandle(_jnt_name),
366  &_jnt_cmd);
367  _jnt_cmd_interface.registerHandle(_handle);
368 
369  ROS_INFO_STREAM("Registered joint '" << _jnt_name << " ' in the CommandJointInterface");
370  }
371 
372 private:
373  // common
375  //-- actual joint(single actuator)
376  //---- joint name
377  std::string rear_wheel_jnt_name_;
378  //---- joint interface parameters
382  //---- joint interface command
384  //---- Hardware interface: joint
386  //hardware_interface::JointStateInterface wheel_jnt_state_interface_;
387  //
388  //-- virtual joints(two rear wheels)
389  //---- joint name
390  std::vector<std::string> virtual_rear_wheel_jnt_names_;
391  //---- joint interface parameters
392  std::vector<double> virtual_rear_wheel_jnt_pos_;
393  std::vector<double> virtual_rear_wheel_jnt_vel_;
394  std::vector<double> virtual_rear_wheel_jnt_eff_;
395  //---- joint interface command
396  std::vector<double> virtual_rear_wheel_jnt_vel_cmd_;
397  //-- virtual joints(two front wheels)
398  //---- joint name
399  std::vector<std::string> virtual_front_wheel_jnt_names_;
400  //---- joint interface parameters
401  std::vector<double> virtual_front_wheel_jnt_pos_;
402  std::vector<double> virtual_front_wheel_jnt_vel_;
403  std::vector<double> virtual_front_wheel_jnt_eff_;
404  //---- joint interface command
405  std::vector<double> virtual_front_wheel_jnt_vel_cmd_;
406 
407  // front steer
408  //-- actual joint(single actuator)
409  //---- joint name
411  //---- joint interface parameters
415  //---- joint interface command
417  //---- Hardware interface: joint
419  //hardware_interface::JointStateInterface steer_jnt_state_interface_;
420  //
421  //-- virtual joints(two steers)
422  //---- joint name
423  std::vector<std::string> virtual_front_steer_jnt_names_;
424  //---- joint interface parameters
425  std::vector<double> virtual_front_steer_jnt_pos_;
426  std::vector<double> virtual_front_steer_jnt_vel_;
427  std::vector<double> virtual_front_steer_jnt_eff_;
428  //---- joint interface command
429  std::vector<double> virtual_front_steer_jnt_pos_cmd_;
430 
431  // Wheel separation, wrt the midpoint of the wheel width:
433  // Wheel separation, wrt the midpoint of the wheel width:
435 
436  std::string ns_;
437  bool running_;
438 
442 };
std::vector< double > virtual_rear_wheel_jnt_eff_
std::vector< double > virtual_front_wheel_jnt_vel_cmd_
hardware_interface::JointStateInterface jnt_state_interface_
void getSteerJointNames(ros::NodeHandle &_nh)
void registerCommandJointInterfaceHandle(hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_cmd)
bool stopCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::vector< double > virtual_rear_wheel_jnt_pos_
std::vector< double > virtual_front_steer_jnt_pos_cmd_
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
hardware_interface::VelocityJointInterface rear_wheel_jnt_vel_cmd_interface_
std::vector< double > virtual_front_steer_jnt_vel_
void registerInterfaceHandles(hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff, double &_jnt_cmd)
hardware_interface::PositionJointInterface front_steer_jnt_pos_cmd_interface_
void registerJointStateInterfaceHandle(hardware_interface::JointStateInterface &_jnt_state_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff)
std::vector< double > virtual_front_steer_jnt_pos_
void getJointNames(ros::NodeHandle &_nh)
bool getParam(const std::string &key, std::string &s) const
ros::ServiceServer stop_srv_
std::vector< double > virtual_rear_wheel_jnt_vel_cmd_
std::vector< double > virtual_front_steer_jnt_eff_
std::vector< double > virtual_front_wheel_jnt_eff_
std::vector< double > virtual_rear_wheel_jnt_vel_
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
void getWheelJointNames(ros::NodeHandle &_nh)
std::vector< std::string > virtual_front_steer_jnt_names_
#define ROS_INFO_STREAM(args)
std::vector< double > virtual_front_wheel_jnt_vel_
bool startCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::Duration getPeriod() const
static Time now()
std::vector< std::string > virtual_front_wheel_jnt_names_
std::vector< double > virtual_front_wheel_jnt_pos_
std::vector< std::string > virtual_rear_wheel_jnt_names_
ros::ServiceServer start_srv_


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