00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2014-2015, Fetch Robotics Inc. 00005 * Copyright (c) 2013, Unbounded Robotics Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of Unbounded Robotics nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 // Author: Michael Ferguson 00037 00038 #ifndef ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H 00039 #define ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H 00040 00041 #include <string> 00042 #include <boost/shared_ptr.hpp> 00043 #include <boost/thread/mutex.hpp> 00044 00045 #include <ros/ros.h> 00046 #include <robot_controllers_interface/controller.h> 00047 #include <robot_controllers_interface/controller_manager.h> 00048 #include <robot_controllers_interface/joint_handle.h> 00049 #include <tf/transform_broadcaster.h> 00050 00051 #include <geometry_msgs/Twist.h> 00052 #include <nav_msgs/Odometry.h> 00053 #include <sensor_msgs/LaserScan.h> 00054 00055 namespace robot_controllers 00056 { 00057 00063 class DiffDriveBaseController : public Controller 00064 { 00065 public: 00066 DiffDriveBaseController(); 00067 virtual ~DiffDriveBaseController() {} 00068 00076 virtual int init(ros::NodeHandle& nh, ControllerManager* manager); 00077 00083 virtual bool start(); 00084 00092 virtual bool stop(bool force); 00093 00100 virtual bool reset(); 00101 00107 virtual void update(const ros::Time& now, const ros::Duration& dt); 00108 00110 virtual std::string getType() 00111 { 00112 return "robot_controllers/DiffDriveBaseController"; 00113 } 00114 00116 virtual std::vector<std::string> getCommandedNames(); 00117 00119 virtual std::vector<std::string> getClaimedNames(); 00120 00122 void command(const geometry_msgs::TwistConstPtr& msg); 00123 00124 private: 00125 bool initialized_; 00126 ControllerManager* manager_; 00127 00128 void publishCallback(const ros::TimerEvent& event); 00129 void scanCallback(const sensor_msgs::LaserScanConstPtr& scan); 00130 00131 // Set base wheel speeds in m/s 00132 void setCommand(float left, float right); 00133 00134 JointHandlePtr left_; 00135 JointHandlePtr right_; 00136 00137 double track_width_; 00138 double radians_per_meter_; 00139 double theta_; 00140 00141 double wheel_rotating_threshold_; 00142 double rotating_threshold_; 00143 double moving_threshold_; 00144 00145 double max_velocity_x_; 00146 double max_velocity_r_; 00147 double max_acceleration_x_; 00148 double max_acceleration_r_; 00149 00150 // Laser can provide additional safety limits on velocity 00151 double safety_scaling_; 00152 double safety_scaling_distance_; 00153 double robot_width_; 00154 ros::Time last_laser_scan_; 00155 00156 // These are the inputs from the ROS topic 00157 boost::mutex command_mutex_; 00158 double desired_x_; 00159 double desired_r_; 00160 00161 // These are from controller update 00162 float last_sent_x_; 00163 float last_sent_r_; 00164 00165 float left_last_position_; 00166 float right_last_position_; 00167 double left_last_timestamp_; 00168 double right_last_timestamp_; 00169 00170 ros::Time last_command_; 00171 ros::Time last_update_; 00172 ros::Duration timeout_; 00173 00174 boost::mutex odom_mutex_; 00175 nav_msgs::Odometry odom_; 00176 ros::Publisher odom_pub_; 00177 ros::Timer odom_timer_; 00178 ros::Subscriber cmd_sub_, scan_sub_; 00179 00180 boost::shared_ptr<tf::TransformBroadcaster> broadcaster_; 00181 bool publish_tf_; 00182 00183 bool enabled_; 00184 bool ready_; 00185 }; 00186 00187 typedef boost::shared_ptr<DiffDriveBaseController> DiffDriveBaseControllerPtr; 00188 00189 } // namespace robot_controllers 00190 00191 #endif // ROBOT_CONTROLLERS_DIFF_DRIVE_BASE_H