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>
54 #include <tf/tfMessage.h>
55 
57 
68  : public controller_interface::Controller<hardware_interface::VelocityJointInterface>
69  {
70  public:
72 
80  ros::NodeHandle& root_nh,
81  ros::NodeHandle &controller_nh);
82 
88  void update(const ros::Time& time, const ros::Duration& period);
89 
94  void starting(const ros::Time& time);
95 
100  void stopping(const ros::Time& /*time*/);
101 
102  private:
103  std::string name_;
104 
108  bool open_loop_;
109 
111  std::vector<hardware_interface::JointHandle> left_wheel_joints_;
112  std::vector<hardware_interface::JointHandle> right_wheel_joints_;
113 
114  // Previous time
116 
118  std::vector<double> vel_left_previous_;
119  std::vector<double> vel_right_previous_;
120 
124 
126  struct Commands
127  {
128  double lin;
129  double ang;
131 
132  Commands() : lin(0.0), ang(0.0), stamp(0.0) {}
133  };
135  Commands command_struct_;
137 
139  std::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped> > cmd_vel_pub_;
140 
142  std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_;
143  std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_;
145 
147  std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::JointTrajectoryControllerState> > controller_state_pub_;
148 
150  double wheel_separation_;
151 
153  double wheel_radius_;
154 
159 
161  double cmd_vel_timeout_;
162 
165 
167  std::string base_frame_id_;
168 
170  std::string odom_frame_id_;
171 
173  bool enable_odom_tf_;
174 
177 
183 
185  bool publish_cmd_;
186 
189 
190  // A struct to hold dynamic parameters
191  // set from dynamic_reconfigure server
193  {
194  bool update;
195 
199 
201 
202  double publish_rate;
204 
205  DynamicParams()
209  , publish_cmd(false)
210  , publish_rate(50)
212  {}
213 
214  friend std::ostream& operator<<(std::ostream& os, const DynamicParams& params)
215  {
216  os << "DynamicParams:\n"
217  //
218  << "\tOdometry parameters:\n"
219  << "\t\tleft wheel radius multiplier: " << params.left_wheel_radius_multiplier << "\n"
220  << "\t\tright wheel radius multiplier: " << params.right_wheel_radius_multiplier << "\n"
221  << "\t\twheel separation multiplier: " << params.wheel_separation_multiplier << "\n"
222  //
223  << "\tPublication parameters:\n"
224  << "\t\tPublish executed velocity command: " << (params.publish_cmd?"enabled":"disabled") << "\n"
225  << "\t\tPublication rate: " << params.publish_rate << "\n"
226  << "\t\tPublish frame odom on tf: " << (params.enable_odom_tf?"enabled":"disabled");
227 
228  return os;
229  }
230  };
231 
233 
235  typedef dynamic_reconfigure::Server<DiffDriveControllerConfig> ReconfigureServer;
236  std::shared_ptr<ReconfigureServer> dyn_reconf_server_;
237  boost::recursive_mutex dyn_reconf_server_mutex_;
238 
239  private:
243  void brake();
244 
249  void cmdVelCallback(const geometry_msgs::Twist& command);
250 
259  bool getWheelNames(ros::NodeHandle& controller_nh,
260  const std::string& wheel_param,
261  std::vector<std::string>& wheel_names);
262 
270  const std::string& left_wheel_name,
271  const std::string& right_wheel_name,
272  bool lookup_wheel_separation,
273  bool lookup_wheel_radius);
274 
280  void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
281 
288  void reconfCallback(DiffDriveControllerConfig& config, uint32_t /*level*/);
289 
293  void updateDynamicParams();
294 
304  void publishWheelData(const ros::Time& time,
305  const ros::Duration& period,
306  Commands& curr_cmd,
307  double wheel_separation,
308  double left_wheel_radius,
309  double right_wheel_radius);
310  };
311 
312 } // namespace diff_drive_controller
realtime_tools::RealtimeBuffer
diff_drive_controller::DiffDriveController::publish_wheel_joint_controller_state_
bool publish_wheel_joint_controller_state_
Publish wheel data:
Definition: diff_drive_controller.h:252
diff_drive_controller::DiffDriveController::sub_command_
ros::Subscriber sub_command_
Definition: diff_drive_controller.h:200
realtime_publisher.h
diff_drive_controller::DiffDriveController::last0_cmd_
Commands last0_cmd_
Definition: diff_drive_controller.h:244
diff_drive_controller::DiffDriveController::publish_period_
ros::Duration publish_period_
Odometry related:
Definition: diff_drive_controller.h:170
diff_drive_controller::DiffDriveController::setOdomParamsFromUrdf
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.
Definition: diff_drive_controller.cpp:620
diff_drive_controller::DiffDriveController::DynamicParams::left_wheel_radius_multiplier
double left_wheel_radius_multiplier
Definition: diff_drive_controller.h:260
diff_drive_controller::DiffDriveController::ReconfigureServer
dynamic_reconfigure::Server< DiffDriveControllerConfig > ReconfigureServer
Dynamic Reconfigure server.
Definition: diff_drive_controller.h:299
diff_drive_controller::DiffDriveController::Commands::ang
double ang
Definition: diff_drive_controller.h:193
diff_drive_controller::DiffDriveController::odometry_
Odometry odometry_
Definition: diff_drive_controller.h:208
diff_drive_controller::DiffDriveController::DynamicParams::publish_rate
double publish_rate
Definition: diff_drive_controller.h:266
diff_drive_controller::DiffDriveController::dyn_reconf_server_
std::shared_ptr< ReconfigureServer > dyn_reconf_server_
Definition: diff_drive_controller.h:300
diff_drive_controller::DiffDriveController::DynamicParams::operator<<
friend std::ostream & operator<<(std::ostream &os, const DynamicParams &params)
Definition: diff_drive_controller.h:278
realtime_buffer.h
diff_drive_controller::DiffDriveController::vel_left_desired_previous_
double vel_left_desired_previous_
Previous velocities from the encoders:
Definition: diff_drive_controller.h:186
diff_drive_controller::DiffDriveController::init
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
Definition: diff_drive_controller.cpp:166
diff_drive_controller::DiffDriveController::DynamicParams::update
bool update
Definition: diff_drive_controller.h:258
diff_drive_controller::DiffDriveController::vel_right_previous_
std::vector< double > vel_right_previous_
Definition: diff_drive_controller.h:183
diff_drive_controller::DiffDriveController::right_wheel_joints_
std::vector< hardware_interface::JointHandle > right_wheel_joints_
Definition: diff_drive_controller.h:176
diff_drive_controller::DiffDriveController::command_struct_
Commands command_struct_
Definition: diff_drive_controller.h:199
diff_drive_controller::DiffDriveController::update
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
Definition: diff_drive_controller.cpp:391
diff_drive_controller::DiffDriveController::Commands::lin
double lin
Definition: diff_drive_controller.h:192
odometry.h
diff_drive_controller
Definition: diff_drive_controller.h:56
diff_drive_controller::DiffDriveController::name_
std::string name_
Definition: diff_drive_controller.h:167
controller_interface::Controller
diff_drive_controller::DiffDriveController::publish_cmd_
bool publish_cmd_
Publish limited velocity:
Definition: diff_drive_controller.h:249
diff_drive_controller::DiffDriveController::cmd_vel_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::TwistStamped > > cmd_vel_pub_
Publish executed commands.
Definition: diff_drive_controller.h:203
diff_drive_controller::DiffDriveController::setOdomPubFields
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
Definition: diff_drive_controller.cpp:689
diff_drive_controller::DiffDriveController::cmd_vel_timeout_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
Definition: diff_drive_controller.h:225
diff_drive_controller::DiffDriveController::Commands::Commands
Commands()
Definition: diff_drive_controller.h:196
hardware_interface::VelocityJointInterface
diff_drive_controller::DiffDriveController::DynamicParams::DynamicParams
DynamicParams()
Definition: diff_drive_controller.h:269
diff_drive_controller::DiffDriveController::vel_right_desired_previous_
double vel_right_desired_previous_
Definition: diff_drive_controller.h:187
diff_drive_controller::DiffDriveController::dynamic_params_
realtime_tools::RealtimeBuffer< DynamicParams > dynamic_params_
Definition: diff_drive_controller.h:296
diff_drive_controller::DiffDriveController::dyn_reconf_server_mutex_
boost::recursive_mutex dyn_reconf_server_mutex_
Definition: diff_drive_controller.h:301
diff_drive_controller::DiffDriveController::command_
realtime_tools::RealtimeBuffer< Commands > command_
Definition: diff_drive_controller.h:198
diff_drive_controller::DiffDriveController::DynamicParams::enable_odom_tf
bool enable_odom_tf
Definition: diff_drive_controller.h:267
controller.h
joint_command_interface.h
diff_drive_controller::DiffDriveController::limiter_ang_
SpeedLimiter limiter_ang_
Definition: diff_drive_controller.h:246
diff_drive_controller::DiffDriveController::stopping
void stopping(const ros::Time &)
Stops controller.
Definition: diff_drive_controller.cpp:517
diff_drive_controller::DiffDriveController::DynamicParams::wheel_separation_multiplier
double wheel_separation_multiplier
Definition: diff_drive_controller.h:262
diff_drive_controller::DiffDriveController::allow_multiple_cmd_vel_publishers_
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
Definition: diff_drive_controller.h:228
diff_drive_controller::DiffDriveController::wheel_joints_size_
size_t wheel_joints_size_
Number of wheel joints:
Definition: diff_drive_controller.h:240
diff_drive_controller::DiffDriveController
Definition: diff_drive_controller.h:99
diff_drive_controller::DiffDriveController::getWheelNames
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.
Definition: diff_drive_controller.cpp:567
diff_drive_controller::DiffDriveController::enable_odom_tf_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
Definition: diff_drive_controller.h:237
diff_drive_controller::DiffDriveController::brake
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
Definition: diff_drive_controller.cpp:522
diff_drive_controller::DiffDriveController::left_wheel_joints_
std::vector< hardware_interface::JointHandle > left_wheel_joints_
Hardware handles:
Definition: diff_drive_controller.h:175
diff_drive_controller::DiffDriveController::wheel_separation_multiplier_
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
Definition: diff_drive_controller.h:220
diff_drive_controller::DiffDriveController::wheel_radius_
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
Definition: diff_drive_controller.h:217
diff_drive_controller::DiffDriveController::last1_cmd_
Commands last1_cmd_
Speed limiters:
Definition: diff_drive_controller.h:243
diff_drive_controller::DiffDriveController::left_wheel_radius_multiplier_
double left_wheel_radius_multiplier_
Definition: diff_drive_controller.h:221
diff_drive_controller::DiffDriveController::base_frame_id_
std::string base_frame_id_
Frame to use for the robot base:
Definition: diff_drive_controller.h:231
diff_drive_controller::DiffDriveController::DynamicParams::publish_cmd
bool publish_cmd
Definition: diff_drive_controller.h:264
diff_drive_controller::DiffDriveController::open_loop_
bool open_loop_
Definition: diff_drive_controller.h:172
ros::Time
diff_drive_controller::DiffDriveController::odom_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
Definition: diff_drive_controller.h:206
diff_drive_controller::DiffDriveController::odom_frame_id_
std::string odom_frame_id_
Frame to use for odometry and odom tf:
Definition: diff_drive_controller.h:234
diff_drive_controller::DiffDriveController::reconfCallback
void reconfCallback(DiffDriveControllerConfig &config, uint32_t)
Callback for dynamic_reconfigure server.
Definition: diff_drive_controller.cpp:736
diff_drive_controller::DiffDriveController::Commands
Velocity command related:
Definition: diff_drive_controller.h:190
diff_drive_controller::DiffDriveController::tf_odom_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
Definition: diff_drive_controller.h:207
diff_drive_controller::DiffDriveController::DynamicParams
Definition: diff_drive_controller.h:256
diff_drive_controller::DiffDriveController::wheel_separation_
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
Definition: diff_drive_controller.h:214
speed_limiter.h
diff_drive_controller::DiffDriveController::Commands::stamp
ros::Time stamp
Definition: diff_drive_controller.h:194
diff_drive_controller::DiffDriveController::updateDynamicParams
void updateDynamicParams()
Update the dynamic parameters in the RT loop.
Definition: diff_drive_controller.cpp:752
diff_drive_controller::DiffDriveController::publishWheelData
void publishWheelData(const ros::Time &time, const ros::Duration &period, Commands &curr_cmd, double wheel_separation, double left_wheel_radius, double right_wheel_radius)
Definition: diff_drive_controller.cpp:765
diff_drive_controller::DiffDriveController::DiffDriveController
DiffDriveController()
Definition: diff_drive_controller.cpp:147
diff_drive_controller::DiffDriveController::vel_left_previous_
std::vector< double > vel_left_previous_
Previous velocities from the encoders:
Definition: diff_drive_controller.h:182
diff_drive_controller::DiffDriveController::controller_state_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > > controller_state_pub_
Controller state publisher.
Definition: diff_drive_controller.h:211
diff_drive_controller::DiffDriveController::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
Definition: diff_drive_controller.cpp:532
diff_drive_controller::DiffDriveController::right_wheel_radius_multiplier_
double right_wheel_radius_multiplier_
Definition: diff_drive_controller.h:222
diff_drive_controller::DiffDriveController::limiter_lin_
SpeedLimiter limiter_lin_
Definition: diff_drive_controller.h:245
ros::Duration
diff_drive_controller::DiffDriveController::starting
void starting(const ros::Time &time)
Starts controller.
Definition: diff_drive_controller.cpp:506
diff_drive_controller::DiffDriveController::DynamicParams::right_wheel_radius_multiplier
double right_wheel_radius_multiplier
Definition: diff_drive_controller.h:261
diff_drive_controller::SpeedLimiter
Definition: speed_limiter.h:77
ros::NodeHandle
ros::Subscriber
diff_drive_controller::DiffDriveController::time_previous_
ros::Time time_previous_
Definition: diff_drive_controller.h:179
diff_drive_controller::DiffDriveController::last_state_publish_time_
ros::Time last_state_publish_time_
Definition: diff_drive_controller.h:171
diff_drive_controller::Odometry
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition: odometry.h:91


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri May 24 2024 02:41:04