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 <nav_msgs/Odometry.h>
00044 #include <tf/tfMessage.h>
00045
00046 #include <realtime_tools/realtime_buffer.h>
00047 #include <realtime_tools/realtime_publisher.h>
00048
00049 #include <mecanum_drive_controller/odometry.h>
00050 #include <mecanum_drive_controller/speed_limiter.h>
00051
00052 namespace mecanum_drive_controller
00053 {
00054
00064 class MecanumDriveController
00065 : public controller_interface::Controller<hardware_interface::VelocityJointInterface>
00066 {
00067 public:
00068 MecanumDriveController();
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& 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 hardware_interface::JointHandle wheel0_jointHandle_;
00109 hardware_interface::JointHandle wheel1_jointHandle_;
00110 hardware_interface::JointHandle wheel2_jointHandle_;
00111 hardware_interface::JointHandle wheel3_jointHandle_;
00112
00114 struct Commands
00115 {
00116 double linX;
00117 double linY;
00118 double ang;
00119 ros::Time stamp;
00120
00121 Commands() : linX(0.0), linY(0.0), ang(0.0), stamp(0.0) {}
00122 };
00123 realtime_tools::RealtimeBuffer<Commands> command_;
00124 Commands command_struct_;
00125 ros::Subscriber sub_command_;
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 geometry_msgs::TransformStamped odom_frame_;
00132
00134 bool use_realigned_roller_joints_;
00135 double wheels_k_;
00136 double wheels_radius_;
00137 double wheel_separation_x_;
00138 double wheel_separation_y_;
00139
00141 double cmd_vel_timeout_;
00142
00144 std::string base_frame_id_;
00145
00147 bool enable_odom_tf_;
00148
00150 size_t wheel_joints_size_;
00151
00152
00153 Commands last_cmd_;
00154 SpeedLimiter limiter_linX_;
00155 SpeedLimiter limiter_linY_;
00156 SpeedLimiter limiter_ang_;
00157
00158 private:
00162 void brake();
00163
00168 void cmdVelCallback(const geometry_msgs::Twist& command);
00169
00178 bool setWheelParamsFromUrdf(ros::NodeHandle& root_nh,
00179 ros::NodeHandle &controller_nh,
00180 const std::string& wheel0_name,
00181 const std::string& wheel1_name,
00182 const std::string& wheel2_name,
00183 const std::string& wheel3_name);
00184
00191 bool getWheelRadius(const boost::shared_ptr<urdf::ModelInterface> model, const boost::shared_ptr<const urdf::Link>& wheel_link, double& wheel_radius);
00192
00198 void setupRtPublishersMsg(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
00199
00200 };
00201
00202 PLUGINLIB_EXPORT_CLASS(mecanum_drive_controller::MecanumDriveController, controller_interface::ControllerBase)
00203
00204 }