Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <controller_interface/controller.h>
00040 #include <hardware_interface/joint_command_interface.h>
00041 #include <pluginlib/class_list_macros.h>
00042
00043 #include <geometry_msgs/TwistStamped.h>
00044 #include <nav_msgs/Odometry.h>
00045 #include <tf/tfMessage.h>
00046
00047 #include <realtime_tools/realtime_buffer.h>
00048 #include <realtime_tools/realtime_publisher.h>
00049
00050 #include <diff_drive_controller/odometry.h>
00051 #include <diff_drive_controller/speed_limiter.h>
00052
00053 namespace diff_drive_controller{
00054
00064 class DiffDriveController
00065 : public controller_interface::Controller<hardware_interface::VelocityJointInterface>
00066 {
00067 public:
00068 DiffDriveController();
00069
00076 bool init(hardware_interface::VelocityJointInterface* hw,
00077 ros::NodeHandle& root_nh,
00078 ros::NodeHandle &controller_nh);
00079
00085 void update(const ros::Time& time, const ros::Duration& period);
00086
00091 void starting(const ros::Time& time);
00092
00097 void stopping(const ros::Time& );
00098
00099 private:
00100 std::string name_;
00101
00103 ros::Duration publish_period_;
00104 ros::Time last_state_publish_time_;
00105 bool open_loop_;
00106
00108 std::vector<hardware_interface::JointHandle> left_wheel_joints_;
00109 std::vector<hardware_interface::JointHandle> right_wheel_joints_;
00110
00112 struct Commands
00113 {
00114 double lin;
00115 double ang;
00116 ros::Time stamp;
00117
00118 Commands() : lin(0.0), ang(0.0), stamp(0.0) {}
00119 };
00120 realtime_tools::RealtimeBuffer<Commands> command_;
00121 Commands command_struct_;
00122 ros::Subscriber sub_command_;
00123
00125 boost::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped> > cmd_vel_pub_;
00126
00128 boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_;
00129 boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_;
00130 Odometry odometry_;
00131
00133 double wheel_separation_;
00134
00136 double wheel_radius_;
00137
00139 double wheel_separation_multiplier_;
00140 double wheel_radius_multiplier_;
00141
00143 double cmd_vel_timeout_;
00144
00146 bool allow_multiple_cmd_vel_publishers_;
00147
00149 std::string base_frame_id_;
00150
00152 std::string odom_frame_id_;
00153
00155 bool enable_odom_tf_;
00156
00158 size_t wheel_joints_size_;
00159
00161 Commands last1_cmd_;
00162 Commands last0_cmd_;
00163 SpeedLimiter limiter_lin_;
00164 SpeedLimiter limiter_ang_;
00165
00167 bool publish_cmd_;
00168
00169 private:
00173 void brake();
00174
00179 void cmdVelCallback(const geometry_msgs::Twist& command);
00180
00189 bool getWheelNames(ros::NodeHandle& controller_nh,
00190 const std::string& wheel_param,
00191 std::vector<std::string>& wheel_names);
00192
00199 bool setOdomParamsFromUrdf(ros::NodeHandle& root_nh,
00200 const std::string& left_wheel_name,
00201 const std::string& right_wheel_name,
00202 bool lookup_wheel_separation,
00203 bool lookup_wheel_radius);
00204
00210 void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
00211
00212 };
00213
00214 PLUGINLIB_EXPORT_CLASS(diff_drive_controller::DiffDriveController, controller_interface::ControllerBase);
00215 }