ackermann_steering_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  * Author: Masaru Morita
38  */
39 
43 
44 #include <nav_msgs/Odometry.h>
45 #include <tf/tfMessage.h>
46 
49 
52 
54 
66  hardware_interface::PositionJointInterface,
67  hardware_interface::VelocityJointInterface>
68  {
69  public:
71 
78  bool init(//hardware_interface::VelocityJointInterface *hw,
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 
109 
113 
115  struct Commands
116  {
117  double lin;
118  double ang;
120 
121  Commands() : lin(0.0), ang(0.0), stamp(0.0) {}
122  };
126 
131 
134 
137 
142 
145 
148 
150  std::string base_frame_id_;
151 
153  std::string odom_frame_id_;
154 
157 
160 
163 
169 
170  private:
174  void brake();
175 
180  void cmdVelCallback(const geometry_msgs::Twist& command);
181 
189  const std::string rear_wheel_name,
190  const std::string front_steer_name,
191  bool lookup_wheel_separation_h,
192  bool lookup_wheel_radius);
193 
199  void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
200 
201  };
202 
203 } // namespace ackermann_drive_controller
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
bool enable_odom_tf_
Whether to publish odometry to tf or not:
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
Definition: odometry.h:60
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string rear_wheel_name, const std::string front_steer_name, bool lookup_wheel_separation_h, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double wheel_separation_h_multiplier_
Wheel separation and radius calibration multipliers:
std::string odom_frame_id_
Frame to use for odometry and odom tf:
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
double wheel_separation_h_
Wheel separation, wrt the midpoint of the wheel width:
hardware_interface::JointHandle rear_wheel_joint_
Hardware handles:
boost::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.
double wheel_radius_
Wheel radius (assuming it&#39;s the same for the left and right wheels):
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.


ackermann_steering_controller
Author(s): Masaru Morita
autogenerated on Sat Apr 18 2020 03:58:07