Go to the documentation of this file.00001
00002
00003
00004 #include <ros/ros.h>
00005 #include <std_msgs/Float64.h>
00006 #include <std_srvs/Empty.h>
00007
00008
00009 #include <controller_manager/controller_manager.h>
00010 #include <hardware_interface/joint_command_interface.h>
00011 #include <hardware_interface/joint_state_interface.h>
00012 #include <hardware_interface/robot_hw.h>
00013 #include <realtime_tools/realtime_buffer.h>
00014
00015
00016 #include <limits>
00017
00018
00019 #include <sstream>
00020
00021 class Ackermann : public hardware_interface::RobotHW
00022 {
00023 public:
00024 Ackermann()
00025 : running_(true)
00026 , start_srv_(nh_.advertiseService("start", &Ackermann::start_callback, this))
00027 , stop_srv_(nh_.advertiseService("stop", &Ackermann::stop_callback, this))
00028 {
00029 std::vector<std::string> velocity_joints_name = {"front_left_wheel", "front_right_wheel",
00030 "rear_left_wheel", "rear_right_wheel"};
00031
00032 for (unsigned int i = 0; i < 4; ++i)
00033 {
00034
00035 hardware_interface::JointStateHandle state_handle(velocity_joints_name[i], &joints_[i].position, &joints_[i].velocity, &joints_[i].effort);
00036 jnt_state_interface_.registerHandle(state_handle);
00037
00038 hardware_interface::JointHandle vel_handle(state_handle, &joints_[i].velocity_command);
00039 jnt_vel_interface_.registerHandle(vel_handle);
00040 }
00041
00042 std::vector<std::string> position_joints_name = {"front_left_steering_joint", "front_right_steering_joint"};
00043
00044 for (unsigned int i = 0; i < 2; ++i)
00045 {
00046 hardware_interface::JointStateHandle state_handle(position_joints_name[i], &steering_joints_[i].position, &steering_joints_[i].velocity, &steering_joints_[i].effort);
00047 jnt_state_interface_.registerHandle(state_handle);
00048
00049 hardware_interface::JointHandle pos_handle(state_handle, &steering_joints_[i].position_command);
00050 jnt_pos_interface_.registerHandle(pos_handle);
00051 }
00052
00053 registerInterface(&jnt_state_interface_);
00054 registerInterface(&jnt_vel_interface_);
00055 registerInterface(&jnt_pos_interface_);
00056 }
00057
00058 ros::Time getTime() const {return ros::Time::now();}
00059 ros::Duration getPeriod() const {return ros::Duration(0.01);}
00060
00061 void read()
00062 {
00063 std::ostringstream os;
00064 for (unsigned int i = 0; i < 3; ++i)
00065 {
00066 os << joints_[i].velocity_command << ", ";
00067 }
00068 os << joints_[3].velocity_command;
00069
00070 ROS_DEBUG_STREAM("Commands for joints: " << os.str());
00071
00072 os.str("");
00073 os << steering_joints_[0].position_command << ", ";
00074 os << steering_joints_[1].position_command;
00075
00076 ROS_DEBUG_STREAM("Commands for steering joints: " << os.str());
00077 }
00078
00079 void write()
00080 {
00081 if (running_)
00082 {
00083 for (unsigned int i = 0; i < 4; ++i)
00084 {
00085
00086
00087
00088 joints_[i].position += joints_[i].velocity*getPeriod().toSec();
00089 joints_[i].velocity = joints_[i].velocity_command;
00090 }
00091 for (unsigned int i = 0; i < 2; ++i)
00092 {
00093 steering_joints_[i].position = steering_joints_[i].position_command;
00094 }
00095 }
00096 else
00097 {
00098 for (unsigned int i = 0; i < 4; ++i)
00099 {
00100 joints_[i].position = std::numeric_limits<double>::quiet_NaN();
00101 joints_[i].velocity = std::numeric_limits<double>::quiet_NaN();
00102 }
00103 for (unsigned int i = 0; i < 2; ++i)
00104 {
00105 steering_joints_[i].position = std::numeric_limits<double>::quiet_NaN();
00106 steering_joints_[i].velocity = std::numeric_limits<double>::quiet_NaN();
00107 }
00108 }
00109 }
00110
00111 bool start_callback(std_srvs::Empty::Request& , std_srvs::Empty::Response& )
00112 {
00113 running_ = true;
00114 return true;
00115 }
00116
00117 bool stop_callback(std_srvs::Empty::Request& , std_srvs::Empty::Response& )
00118 {
00119 running_ = false;
00120 return true;
00121 }
00122
00123 private:
00124 hardware_interface::JointStateInterface jnt_state_interface_;
00125 hardware_interface::VelocityJointInterface jnt_vel_interface_;
00126 hardware_interface::PositionJointInterface jnt_pos_interface_;
00127
00128 struct Joint
00129 {
00130 double position;
00131 double velocity;
00132 double effort;
00133 double velocity_command;
00134
00135 Joint() : position(0), velocity(0), effort(0), velocity_command(0) { }
00136 } joints_[4];
00137
00138 struct SteeringJoint
00139 {
00140 double position;
00141 double velocity;
00142 double effort;
00143 double position_command;
00144
00145 SteeringJoint() : position(0), velocity(0), effort(0), position_command(0) { }
00146 } steering_joints_[2];
00147 bool running_;
00148
00149 ros::NodeHandle nh_;
00150 ros::ServiceServer start_srv_;
00151 ros::ServiceServer stop_srv_;
00152 };