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 <ackermann_msgs/AckermannDrive.h>
00008 #include <tf/tfMessage.h>
00009
00010 #include <realtime_tools/realtime_buffer.h>
00011 #include <realtime_tools/realtime_publisher.h>
00012
00013 #include <ackermann_controller/odometry.h>
00014 #include <ackermann_controller/speed_limiter.h>
00015
00016 namespace ackermann_controller{
00017
00028 class AckermannController
00029 : public controller_interface::ControllerBase
00030 {
00031 public:
00032 AckermannController();
00033
00041 virtual bool initRequest(hardware_interface::RobotHW *const robot_hw,
00042 ros::NodeHandle& root_nh,
00043 ros::NodeHandle &controller_nh,
00044 std::set<std::string>& claimed_resources);
00046 std::string getHardwareInterfaceType() const
00047 {
00048 return "";
00049 }
00050
00051 bool init(hardware_interface::PositionJointInterface* hw_pos,
00052 hardware_interface::VelocityJointInterface* hw_vel,
00053 ros::NodeHandle& root_nh,
00054 ros::NodeHandle &controller_nh);
00055
00061 void update(const ros::Time& time, const ros::Duration& period);
00062
00067 void starting(const ros::Time& time);
00068
00073 void stopping(const ros::Time& time);
00074
00075 private:
00076 std::string name_;
00077
00079 ros::Duration publish_period_;
00080 ros::Time last_state_publish_time_;
00081 bool open_loop_;
00082
00084 std::vector<hardware_interface::JointHandle> front_wheel_joints_;
00085 std::vector<hardware_interface::JointHandle> rear_wheel_joints_;
00086 std::vector<hardware_interface::JointHandle> front_steering_joints_;
00087
00089 struct Commands
00090 {
00091 double lin;
00092 double ang;
00093 double steering;
00094 ros::Time stamp;
00095
00096 Commands() : lin(0.0), ang(0.0), 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_ackermann_;
00104 Commands command_struct_ackermann_;
00105 ros::Subscriber sub_command_ackermann_;
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
00112
00114 double track_;
00115
00117 double front_wheel_radius_, rear_wheel_radius_;
00118
00120 double steering_limit_;
00121
00123 double wheel_base_;
00124
00126 double cmd_vel_timeout_;
00127
00129 std::string base_frame_id_;
00130
00132 bool enable_odom_tf_;
00133
00135 bool enable_twist_cmd_;
00136
00138 Commands last1_cmd_;
00139 Commands last0_cmd_;
00140 SpeedLimiter limiter_lin_;
00141 SpeedLimiter limiter_ang_;
00142
00143 private:
00147 void brake();
00148
00153 void cmdVelCallback(const geometry_msgs::Twist& command);
00154
00159 void cmdAckermannCallback(const ackermann_msgs::AckermannDrive& command);
00160
00169 bool getWheelNames(ros::NodeHandle& controller_nh,
00170 const std::string& wheel_param,
00171 std::vector<std::string>& wheel_names);
00172
00178 void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
00179
00192 void handleSteeringSaturation(double& front_left_steering, double& front_right_steering);
00193
00194 };
00195
00196 PLUGINLIB_EXPORT_CLASS(ackermann_controller::AckermannController, controller_interface::ControllerBase);
00197 }