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 FourWheelSteering : public hardware_interface::RobotHW
00022 {
00023 public:
00024 FourWheelSteering()
00025 : running_(true)
00026 , start_srv_(nh_.advertiseService("start", &FourWheelSteering::start_callback, this))
00027 , stop_srv_(nh_.advertiseService("stop", &FourWheelSteering::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 < velocity_joints_name.size(); ++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 "rear_left_steering_joint", "rear_right_steering_joint"};
00044
00045 for (unsigned int i = 0; i < position_joints_name.size(); ++i)
00046 {
00047 hardware_interface::JointStateHandle state_handle(position_joints_name[i], &steering_joints_[i].position, &steering_joints_[i].velocity, &steering_joints_[i].effort);
00048 jnt_state_interface_.registerHandle(state_handle);
00049
00050 hardware_interface::JointHandle pos_handle(state_handle, &steering_joints_[i].position_command);
00051 jnt_pos_interface_.registerHandle(pos_handle);
00052 }
00053
00054 registerInterface(&jnt_state_interface_);
00055 registerInterface(&jnt_vel_interface_);
00056 registerInterface(&jnt_pos_interface_);
00057 }
00058
00059 ros::Time getTime() const {return ros::Time::now();}
00060 ros::Duration getPeriod() const {return ros::Duration(0.01);}
00061
00062 void read()
00063 {
00064 std::ostringstream os;
00065 for (unsigned int i = 0; i < 3; ++i)
00066 {
00067 os << joints_[i].velocity_command << ", ";
00068 }
00069 os << joints_[3].velocity_command;
00070
00071 ROS_DEBUG_STREAM("Commands for joints: " << os.str());
00072
00073 os.str("");
00074 for (unsigned int i = 0; i < 3; ++i)
00075 {
00076 os << steering_joints_[i].position_command << ", ";
00077 }
00078 os << steering_joints_[3].position_command;
00079 ROS_DEBUG_STREAM("Commands for steering joints: " << os.str());
00080 }
00081
00082 void write()
00083 {
00084 if (running_)
00085 {
00086 for (unsigned int i = 0; i < 4; ++i)
00087 {
00088
00089
00090
00091 joints_[i].position += joints_[i].velocity*getPeriod().toSec();
00092 joints_[i].velocity = joints_[i].velocity_command;
00093 }
00094 for (unsigned int i = 0; i < 4; ++i)
00095 {
00096 steering_joints_[i].position = steering_joints_[i].position_command;
00097 }
00098 }
00099 else
00100 {
00101 for (unsigned int i = 0; i < 4; ++i)
00102 {
00103 joints_[i].position = std::numeric_limits<double>::quiet_NaN();
00104 joints_[i].velocity = std::numeric_limits<double>::quiet_NaN();
00105 }
00106 for (unsigned int i = 0; i < 4; ++i)
00107 {
00108 steering_joints_[i].position = std::numeric_limits<double>::quiet_NaN();
00109 steering_joints_[i].velocity = std::numeric_limits<double>::quiet_NaN();
00110 }
00111 }
00112 }
00113
00114 bool start_callback(std_srvs::Empty::Request& , std_srvs::Empty::Response& )
00115 {
00116 running_ = true;
00117 return true;
00118 }
00119
00120 bool stop_callback(std_srvs::Empty::Request& , std_srvs::Empty::Response& )
00121 {
00122 running_ = false;
00123 return true;
00124 }
00125
00126 private:
00127 hardware_interface::JointStateInterface jnt_state_interface_;
00128 hardware_interface::VelocityJointInterface jnt_vel_interface_;
00129 hardware_interface::PositionJointInterface jnt_pos_interface_;
00130
00131 struct Joint
00132 {
00133 double position;
00134 double velocity;
00135 double effort;
00136 double velocity_command;
00137
00138 Joint() : position(0), velocity(0), effort(0), velocity_command(0) { }
00139 } joints_[4];
00140
00141 struct SteeringJoint
00142 {
00143 double position;
00144 double velocity;
00145 double effort;
00146 double position_command;
00147
00148 SteeringJoint() : position(0), velocity(0), effort(0), position_command(0) { }
00149 } steering_joints_[4];
00150 bool running_;
00151
00152 ros::NodeHandle nh_;
00153 ros::ServiceServer start_srv_;
00154 ros::ServiceServer stop_srv_;
00155 };