double_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: Enrique Fernández
37  */
38 
42 
43 #include <nav_msgs/Odometry.h>
44 #include <tf/tfMessage.h>
45 
48 
51 
53 {
54 
64 class DoubleDiffDriveController: public controller_interface::Controller<hardware_interface::VelocityJointInterface>
65 {
66 public:
68 
76  ros::NodeHandle& root_nh,
77  ros::NodeHandle& controller_nh);
78 
84  void update(const ros::Time& time, const ros::Duration& period);
85 
90  void starting(const ros::Time& time);
91 
96  void stopping(const ros::Time& time);
97 
98 private:
99  std::string name_;
100 
105 
109  // std::vector<hardware_interface::JointHandle> left_wheels_;
110  // std::vector<hardware_interface::JointHandle> right_wheels_;
111 
113  struct Commands
114  {
115  double lin;
116  double ang;
118 
119  Commands() : lin(0.0), ang(0.0), stamp(0.0) {}
120  };
124 
129  geometry_msgs::TransformStamped odom_frame_;
130 
133 
137 
142 
145 
147  std::string base_frame_id_;
148 
151 
154 
155  // Speed limiters:
159 
160 private:
164  void brake();
165 
170  void cmdVelCallback(const geometry_msgs::Twist& command);
171 
179  ros::NodeHandle &controller_nh,
180  const std::string& drive_motor_name,
181  const std::string& steer_motor_name);
182 
188  void setupRtPublishersMsg(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
189 
190 };
191 
193 
194 } // namespace double_diff_drive_controller
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
hardware_interface::JointHandle drive_motor_input_
Hardware handles:
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.
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
Definition: odometry.h:60
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
double wheel_radius_
Wheel radius (assuming it&#39;s the same for the left and right wheels):
bool enable_odom_tf_
Whether to publish odometry to tf or not:
std::string base_frame_id_
Frame to use for the robot base:
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
void setupRtPublishersMsg(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool setWheelParamsFromUrdf(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, const std::string &drive_motor_name, const std::string &steer_motor_name)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:


moose_control
Author(s): Tony Baltovski
autogenerated on Wed Mar 10 2021 03:43:55