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
00040 #include <controller_interface/controller.h>
00041 #include <hardware_interface/joint_command_interface.h>
00042 #include <pluginlib/class_list_macros.h>
00043
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 <steer_drive_controller/odometry.h>
00051 #include <steer_drive_controller/speed_limiter.h>
00052 #include <steer_drive_controller/multi_interface_controller.h>
00053
00054
00055
00056 namespace steer_drive_controller{
00057
00067 class SteerDriveController
00068 : public controller_interface::MultiInterfaceController<
00069 hardware_interface::PositionJointInterface,
00070 hardware_interface::VelocityJointInterface>
00071 {
00072
00073 private:
00074 enum INDX_WHEEL {
00075 INDX_WHEEL_FRNT = 0,
00076 INDX_WHEEL_MID = 1,
00077 INDX_WHEEL_BACK = 2,
00078 };
00079 enum INDX_STEER {
00080 INDX_STEER_FRNT = 0,
00081 INDX_STEER_BACK = 1,
00082 };
00083
00084 enum INDEX_WHEEL {
00085 INDEX_RIGHT = 0,
00086 INDEX_LEFT = 1
00087 };
00088 public:
00089 SteerDriveController();
00090
00097 bool init(
00098 hardware_interface::RobotHW* robot_hw,
00099 ros::NodeHandle& root_nh,
00100 ros::NodeHandle &controller_nh);
00101
00107 void update(const ros::Time& time, const ros::Duration& period);
00108
00113 void starting(const ros::Time& time);
00114
00119 void stopping(const ros::Time& );
00120
00121 private:
00122 std::string name_;
00123
00125 ros::Duration publish_period_;
00126 ros::Time last_state_publish_time_;
00127 bool open_loop_;
00128
00130 hardware_interface::JointHandle rear_wheel_joint_;
00131 hardware_interface::JointHandle front_steer_joint_;
00132
00134 struct Commands
00135 {
00136 double lin;
00137 double ang;
00138 ros::Time stamp;
00139
00140 Commands() : lin(0.0), ang(0.0), stamp(0.0) {}
00141 };
00142 realtime_tools::RealtimeBuffer<Commands> command_;
00143 Commands command_struct_;
00144 ros::Subscriber sub_command_;
00145
00147 boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_;
00148 boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_;
00149 Odometry odometry_;
00150
00152 double wheel_separation_h_;
00153
00155 double wheel_radius_;
00156
00158 double wheel_separation_h_multiplier_;
00159 double wheel_radius_multiplier_;
00160 double steer_pos_multiplier_;
00161
00163 double cmd_vel_timeout_;
00164
00166 bool allow_multiple_cmd_vel_publishers_;
00167
00169 std::string base_frame_id_;
00170
00172 std::string odom_frame_id_;
00173
00175 bool enable_odom_tf_;
00176
00178 size_t wheel_joints_size_;
00179
00181 size_t steer_joints_size_;
00182
00184 Commands last1_cmd_;
00185 Commands last0_cmd_;
00186 SpeedLimiter limiter_lin_;
00187 SpeedLimiter limiter_ang_;
00188
00189
00190 std::string ns_;
00191
00192 private:
00196 void brake();
00197
00202 void cmdVelCallback(const geometry_msgs::Twist& command);
00203
00210 bool setOdomParamsFromUrdf(ros::NodeHandle& root_nh,
00211 const std::string rear_wheel_name,
00212 const std::string front_steer_name,
00213 bool lookup_wheel_separation_h,
00214 bool lookup_wheel_radius);
00215
00221 void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
00222
00223 };
00224
00225 PLUGINLIB_EXPORT_CLASS(steer_drive_controller::SteerDriveController, controller_interface::ControllerBase)
00226 }