diff_drive_controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, PAL Robotics, S.L.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the PAL Robotics nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /*
36  * Author: Bence Magyar, Enrique Fernández
37  */
38 
39 #pragma once
40 
41 
42 #include <control_msgs/JointTrajectoryControllerState.h>
44 #include <diff_drive_controller/DiffDriveControllerConfig.h>
47 #include <dynamic_reconfigure/server.h>
48 #include <geometry_msgs/TwistStamped.h>
50 #include <memory>
51 #include <nav_msgs/Odometry.h>
55 #include <tf/tfMessage.h>
56 
58 
69  : public controller_interface::Controller<hardware_interface::VelocityJointInterface>
70  {
71  public:
73 
81  ros::NodeHandle& root_nh,
82  ros::NodeHandle &controller_nh);
83 
89  void update(const ros::Time& time, const ros::Duration& period);
90 
95  void starting(const ros::Time& time);
96 
101  void stopping(const ros::Time& /*time*/);
102 
103  private:
104  std::string name_;
105 
110 
112  std::vector<hardware_interface::JointHandle> left_wheel_joints_;
113  std::vector<hardware_interface::JointHandle> right_wheel_joints_;
114 
115  // Previous time
117 
119  std::vector<double> vel_left_previous_;
120  std::vector<double> vel_right_previous_;
121 
125 
127  struct Commands
128  {
129  double lin;
130  double ang;
132 
133  Commands() : lin(0.0), ang(0.0), stamp(0.0) {}
134  };
138 
140  std::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped> > cmd_vel_pub_;
141 
143  std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_;
144  std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_;
146 
148  std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::JointTrajectoryControllerState> > controller_state_pub_;
149 
152 
155 
160 
163 
166 
168  std::string base_frame_id_;
169 
171  std::string odom_frame_id_;
172 
175 
178 
184 
187 
190 
191  // A struct to hold dynamic parameters
192  // set from dynamic_reconfigure server
194  {
195  bool update;
196 
200 
202 
203  double publish_rate;
205 
207  : left_wheel_radius_multiplier(1.0)
208  , right_wheel_radius_multiplier(1.0)
209  , wheel_separation_multiplier(1.0)
210  , publish_cmd(false)
211  , publish_rate(50)
212  , enable_odom_tf(true)
213  {}
214 
215  friend std::ostream& operator<<(std::ostream& os, const DynamicParams& params)
216  {
217  os << "DynamicParams:\n"
218  //
219  << "\tOdometry parameters:\n"
220  << "\t\tleft wheel radius multiplier: " << params.left_wheel_radius_multiplier << "\n"
221  << "\t\tright wheel radius multiplier: " << params.right_wheel_radius_multiplier << "\n"
222  << "\t\twheel separation multiplier: " << params.wheel_separation_multiplier << "\n"
223  //
224  << "\tPublication parameters:\n"
225  << "\t\tPublish executed velocity command: " << (params.publish_cmd?"enabled":"disabled") << "\n"
226  << "\t\tPublication rate: " << params.publish_rate << "\n"
227  << "\t\tPublish frame odom on tf: " << (params.enable_odom_tf?"enabled":"disabled");
228 
229  return os;
230  }
231  };
232 
234 
236  typedef dynamic_reconfigure::Server<DiffDriveControllerConfig> ReconfigureServer;
237  std::shared_ptr<ReconfigureServer> dyn_reconf_server_;
238  boost::recursive_mutex dyn_reconf_server_mutex_;
239 
240  private:
244  void brake();
245 
250  void cmdVelCallback(const geometry_msgs::Twist& command);
251 
260  bool getWheelNames(ros::NodeHandle& controller_nh,
261  const std::string& wheel_param,
262  std::vector<std::string>& wheel_names);
263 
271  const std::string& left_wheel_name,
272  const std::string& right_wheel_name,
273  bool lookup_wheel_separation,
274  bool lookup_wheel_radius);
275 
281  void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
282 
289  void reconfCallback(DiffDriveControllerConfig& config, uint32_t /*level*/);
290 
294  void updateDynamicParams();
295 
305  void publishWheelData(const ros::Time& time,
306  const ros::Duration& period,
307  Commands& curr_cmd,
308  double wheel_separation,
309  double left_wheel_radius,
310  double right_wheel_radius);
311  };
312 
314 } // namespace diff_drive_controller
realtime_tools::RealtimeBuffer< Commands > command_
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
void updateDynamicParams()
Update the dynamic parameters in the RT loop.
std::vector< hardware_interface::JointHandle > left_wheel_joints_
Hardware handles:
double wheel_radius_
Wheel radius (assuming it&#39;s the same for the left and right wheels):
std::string odom_frame_id_
Frame to use for odometry and odom tf:
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
size_t wheel_joints_size_
Number of wheel joints:
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.
PLUGINLIB_EXPORT_CLASS(diff_drive_controller::DiffDriveController, controller_interface::ControllerBase)
std::shared_ptr< realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > > controller_state_pub_
Controller state publisher.
std::vector< double > vel_left_previous_
Previous velocities from the encoders:
std::vector< hardware_interface::JointHandle > right_wheel_joints_
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
void starting(const ros::Time &time)
Starts controller.
double vel_left_desired_previous_
Previous velocities from the encoders:
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::TwistStamped > > cmd_vel_pub_
Publish executed commands.
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
realtime_tools::RealtimeBuffer< DynamicParams > dynamic_params_
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
Definition: odometry.h:59
bool publish_wheel_joint_controller_state_
Publish wheel data:
ros::Duration publish_period_
Odometry related:
void publishWheelData(const ros::Time &time, const ros::Duration &period, Commands &curr_cmd, double wheel_separation, double left_wheel_radius, double right_wheel_radius)
std::shared_ptr< ReconfigureServer > dyn_reconf_server_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
friend std::ostream & operator<<(std::ostream &os, const DynamicParams &params)
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string &left_wheel_name, const std::string &right_wheel_name, bool lookup_wheel_separation, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
bool enable_odom_tf_
Whether to publish odometry to tf or not:
void reconfCallback(DiffDriveControllerConfig &config, uint32_t)
Callback for dynamic_reconfigure server.
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
dynamic_reconfigure::Server< DiffDriveControllerConfig > ReconfigureServer
Dynamic Reconfigure server.
void stopping(const ros::Time &)
Stops controller.
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
std::string base_frame_id_
Frame to use for the robot base:


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri Feb 3 2023 03:19:01