rrbot.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics S.L. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00028 // NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials
00029 
00030 // ROS
00031 #include <ros/ros.h>
00032 #include <std_msgs/Float64.h>
00033 
00034 // ros_control
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     // Intialize raw data
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     // Connect and register the joint state interface
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     // Connect and register the joint position interface
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     // Smoothing subscriber
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 }


play_motion
Author(s): Paul Mathieu
autogenerated on Wed Aug 26 2015 15:29:25