Go to the documentation of this file.00001
00002 #include <controller_interface/controller_base.h>
00003 #include <hardware_interface/joint_command_interface.h>
00004 #include <pluginlib/class_list_macros.h>
00005
00006 #include <nav_msgs/Odometry.h>
00007 #include <four_wheel_steering_msgs/FourWheelSteering.h>
00008 #include <tf/tfMessage.h>
00009
00010 #include <realtime_tools/realtime_buffer.h>
00011 #include <realtime_tools/realtime_publisher.h>
00012
00013 #include <four_wheel_steering_controller/odometry.h>
00014 #include <four_wheel_steering_controller/speed_limiter.h>
00015
00016 namespace four_wheel_steering_controller{
00017
00027 class FourWheelSteeringController
00028 : public controller_interface::ControllerBase
00029 {
00030 public:
00031 FourWheelSteeringController();
00032
00039 virtual bool initRequest(hardware_interface::RobotHW *const robot_hw,
00040 ros::NodeHandle& root_nh,
00041 ros::NodeHandle &controller_nh,
00042 std::set<std::string>& claimed_resources);
00044 std::string getHardwareInterfaceType() const
00045 {
00046 return "";
00047 }
00048
00049 bool init(hardware_interface::PositionJointInterface* hw_pos,
00050 hardware_interface::VelocityJointInterface* hw_vel,
00051 ros::NodeHandle& root_nh,
00052 ros::NodeHandle &controller_nh);
00053
00059 void update(const ros::Time& time, const ros::Duration& period);
00060
00065 void starting(const ros::Time& time);
00066
00071 void stopping(const ros::Time& );
00072
00073 private:
00074 std::string name_;
00075
00077 ros::Duration publish_period_;
00078 ros::Time last_state_publish_time_;
00079 bool open_loop_;
00080
00082 std::vector<hardware_interface::JointHandle> front_wheel_joints_;
00083 std::vector<hardware_interface::JointHandle> rear_wheel_joints_;
00084 std::vector<hardware_interface::JointHandle> front_steering_joints_;
00085 std::vector<hardware_interface::JointHandle> rear_steering_joints_;
00086
00088 struct Commands
00089 {
00090 double lin;
00091 double ang;
00092 double front_steering;
00093 double rear_steering;
00094 ros::Time stamp;
00095
00096 Commands() : lin(0.0), ang(0.0), front_steering(0.0), rear_steering(0.0), stamp(0.0) {}
00097 };
00098 realtime_tools::RealtimeBuffer<Commands> command_;
00099 Commands command_struct_;
00100 ros::Subscriber sub_command_;
00101
00103 realtime_tools::RealtimeBuffer<Commands> command_four_wheel_steering_;
00104 Commands command_struct_four_wheel_steering_;
00105 ros::Subscriber sub_command_four_wheel_steering_;
00106
00108 boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_;
00109 boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_;
00110 Odometry odometry_;
00111
00113 double track_;
00114
00116 double wheel_radius_;
00117
00119 double wheel_base_;
00120
00122 double cmd_vel_timeout_;
00123
00125 std::string base_frame_id_;
00126
00128 bool enable_odom_tf_;
00129
00131 bool enable_twist_cmd_;
00132
00134 Commands last1_cmd_;
00135 Commands last0_cmd_;
00136 SpeedLimiter limiter_lin_;
00137 SpeedLimiter limiter_ang_;
00138
00139 private:
00143 void brake();
00144
00149 void cmdVelCallback(const geometry_msgs::Twist& command);
00150
00155 void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering& command);
00156
00165 bool getWheelNames(ros::NodeHandle& controller_nh,
00166 const std::string& wheel_param,
00167 std::vector<std::string>& wheel_names);
00168
00174 void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
00175
00176 };
00177
00178 PLUGINLIB_EXPORT_CLASS(four_wheel_steering_controller::FourWheelSteeringController, controller_interface::ControllerBase);
00179 }