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
00027
00028
00029
00030
00031 #include <ros/ros.h>
00032 #include <std_msgs/Float64.h>
00033
00034
00035 #include <controller_manager/controller_manager.h>
00036 #include <hardware_interface/joint_command_interface.h>
00037 #include <hardware_interface/joint_state_interface.h>
00038 #include <hardware_interface/robot_hw.h>
00039 #include <realtime_tools/realtime_buffer.h>
00040
00041 class Diffbot : public hardware_interface::RobotHW
00042 {
00043 public:
00044 Diffbot()
00045 {
00046
00047 pos_[0] = 0.0; pos_[1] = 0.0;
00048 vel_[0] = 0.0; vel_[1] = 0.0;
00049 eff_[0] = 0.0; eff_[1] = 0.0;
00050 cmd_[0] = 0.0; cmd_[1] = 0.0;
00051
00052
00053 hardware_interface::JointStateHandle state_handle_1("joint_w1", &pos_[0], &vel_[0], &eff_[0]);
00054 jnt_state_interface_.registerHandle(state_handle_1);
00055
00056 hardware_interface::JointStateHandle state_handle_2("joint_w2", &pos_[1], &vel_[1], &eff_[1]);
00057 jnt_state_interface_.registerHandle(state_handle_2);
00058
00059 registerInterface(&jnt_state_interface_);
00060
00061
00062 hardware_interface::JointHandle vel_handle_1(jnt_state_interface_.getHandle("joint_w1"), &cmd_[0]);
00063 jnt_vel_interface_.registerHandle(vel_handle_1);
00064
00065 hardware_interface::JointHandle vel_handle_2(jnt_state_interface_.getHandle("joint_w2"), &cmd_[1]);
00066 jnt_vel_interface_.registerHandle(vel_handle_2);
00067
00068 registerInterface(&jnt_vel_interface_);
00069 }
00070
00071 ros::Time getTime() const {return ros::Time::now();}
00072 ros::Duration getPeriod() const {return ros::Duration(0.01);}
00073
00074 void read()
00075 {
00076 ROS_INFO_STREAM("Commands for joints: " << cmd_[0] << ", " << cmd_[1]);
00077 }
00078
00079 void write()
00080 {
00081 for (unsigned int i = 0; i < 2; ++i)
00082 {
00083 pos_[i] += vel_[i]*getPeriod().toSec();
00084 vel_[i] = cmd_[i];
00085 }
00086 }
00087
00088 private:
00089 hardware_interface::JointStateInterface jnt_state_interface_;
00090 hardware_interface::VelocityJointInterface jnt_vel_interface_;
00091 double cmd_[2];
00092 double pos_[2];
00093 double vel_[2];
00094 double eff_[2];
00095 };
00096
00097 int main(int argc, char **argv)
00098 {
00099 ros::init(argc, argv, "diffbot");
00100 ros::NodeHandle nh;
00101
00102 Diffbot robot;
00103 ROS_WARN_STREAM("period: " << robot.getPeriod().toSec());
00104 controller_manager::ControllerManager cm(&robot, nh);
00105
00106 ros::Rate rate(1.0 / robot.getPeriod().toSec());
00107 ros::AsyncSpinner spinner(1);
00108 spinner.start();
00109 while(ros::ok())
00110 {
00111 robot.read();
00112 cm.update(robot.getTime(), robot.getPeriod());
00113 robot.write();
00114 rate.sleep();
00115 }
00116 spinner.stop();
00117
00118 return 0;
00119 }