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 RRbot : public hardware_interface::RobotHW
00042 {
00043 public:
00044 RRbot()
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("joint1", &pos_[0], &vel_[0], &eff_[0]);
00054 jnt_state_interface_.registerHandle(state_handle_1);
00055
00056 hardware_interface::JointStateHandle state_handle_2("joint2", &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 pos_handle_1(jnt_state_interface_.getHandle("joint1"), &cmd_[0]);
00063 jnt_pos_interface_.registerHandle(pos_handle_1);
00064
00065 hardware_interface::JointHandle pos_handle_2(jnt_state_interface_.getHandle("joint2"), &cmd_[1]);
00066 jnt_pos_interface_.registerHandle(pos_handle_2);
00067
00068 registerInterface(&jnt_pos_interface_);
00069
00070
00071 smoothing_sub_ = ros::NodeHandle().subscribe("smoothing", 1, &RRbot::smoothingCB, this);
00072 smoothing_.initRT(0.0);
00073 }
00074
00075 ros::Time getTime() const {return ros::Time::now();}
00076 ros::Duration getPeriod() const {return ros::Duration(0.01);}
00077
00078 void read() {}
00079
00080 void write()
00081 {
00082 const double smoothing = *(smoothing_.readFromRT());
00083 for (unsigned int i = 0; i < 2; ++i)
00084 {
00085 vel_[i] = (cmd_[i] - pos_[i]) / getPeriod().toSec();
00086
00087 const double next_pos = smoothing * pos_[i] + (1.0 - smoothing) * cmd_[i];
00088 pos_[i] = next_pos;
00089 }
00090 }
00091
00092 private:
00093 hardware_interface::JointStateInterface jnt_state_interface_;
00094 hardware_interface::PositionJointInterface jnt_pos_interface_;
00095 double cmd_[2];
00096 double pos_[2];
00097 double vel_[2];
00098 double eff_[2];
00099
00100 realtime_tools::RealtimeBuffer<double> smoothing_;
00101 void smoothingCB(const std_msgs::Float64& smoothing) {smoothing_.writeFromNonRT(smoothing.data);}
00102
00103 ros::Subscriber smoothing_sub_;
00104 };
00105
00106 int main(int argc, char **argv)
00107 {
00108 ros::init(argc, argv, "rrbot");
00109 ros::NodeHandle nh;
00110
00111 RRbot robot;
00112 controller_manager::ControllerManager cm(&robot, nh);
00113
00114 ros::Rate rate(1.0 / robot.getPeriod().toSec());
00115 ros::AsyncSpinner spinner(1);
00116 spinner.start();
00117 while (ros::ok())
00118 {
00119 robot.read();
00120 cm.update(robot.getTime(), robot.getPeriod());
00121 robot.write();
00122 rate.sleep();
00123 }
00124 spinner.stop();
00125
00126 return 0;
00127 }