diff_drive_base.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014-2015, Fetch Robotics Inc.
5  * Copyright (c) 2013, Unbounded Robotics Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Unbounded Robotics nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 // Author: Michael Ferguson
37 
38 #ifndef ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H
39 #define ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H
40 
41 #include <string>
42 #include <boost/shared_ptr.hpp>
43 #include <boost/thread/mutex.hpp>
44 
45 #include <ros/ros.h>
50 
51 #include <geometry_msgs/Twist.h>
52 #include <nav_msgs/Odometry.h>
53 #include <sensor_msgs/LaserScan.h>
54 
55 namespace robot_controllers
56 {
57 
64 {
65 public:
68 
76  virtual int init(ros::NodeHandle& nh, ControllerManager* manager);
77 
83  virtual bool start();
84 
92  virtual bool stop(bool force);
93 
100  virtual bool reset();
101 
107  virtual void update(const ros::Time& now, const ros::Duration& dt);
108 
110  virtual std::string getType()
111  {
112  return "robot_controllers/DiffDriveBaseController";
113  }
114 
116  virtual std::vector<std::string> getCommandedNames();
117 
119  virtual std::vector<std::string> getClaimedNames();
120 
122  void command(const geometry_msgs::TwistConstPtr& msg);
123 
124 private:
127 
128  void publishCallback(const ros::TimerEvent& event);
129  void scanCallback(const sensor_msgs::LaserScanConstPtr& scan);
130 
131  // Set base wheel speeds in m/s
132  void setCommand(float left, float right);
133 
136 
137  double track_width_;
139  double theta_;
140 
144 
149 
150  // Laser can provide additional safety limits on velocity
153  double robot_width_;
155 
156  // These are the inputs from the ROS topic
157  boost::mutex command_mutex_;
158  double desired_x_;
159  double desired_r_;
160 
161  // These are from controller update
164 
169 
173 
174  boost::mutex odom_mutex_;
175  nav_msgs::Odometry odom_;
179 
182 
183  bool enabled_;
184  bool ready_;
185 };
186 
188 
189 } // namespace robot_controllers
190 
191 #endif // ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H
double rotating_threshold_
Threshold for wheel velocity to be "moving".
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
virtual std::string getType()
Get the type of this controller.
void publishCallback(const ros::TimerEvent &event)
void setCommand(float left, float right)
void command(const geometry_msgs::TwistConstPtr &msg)
Command callback from either a ROS topic, or a higher controller.
virtual bool start()
Attempt to start the controller. This should be called only by the ControllerManager instance...
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan)
boost::shared_ptr< DiffDriveBaseController > DiffDriveBaseControllerPtr
double moving_threshold_
Threshold for dr to be considered "moving".
double max_velocity_x_
Threshold for dx to be considered "moving".
virtual bool stop(bool force)
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual bool reset()
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getClaimedNames()
Get the names of joints/controllers which this controller exclusively claims.
boost::shared_ptr< tf::TransformBroadcaster > broadcaster_
virtual std::vector< std::string > getCommandedNames()
Get the names of joints/controllers which this controller commands.
ROS-aware controller to manage a differential drive mobile base. This subcribes to cmd_vel topic...
virtual void update(const ros::Time &now, const ros::Duration &dt)
This is the update loop for the controller.


robot_controllers
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:39