diffbot.h
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, Inc. 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 #include <std_srvs/Empty.h>
00034 
00035 // ros_control
00036 #include <controller_manager/controller_manager.h>
00037 #include <hardware_interface/joint_command_interface.h>
00038 #include <hardware_interface/joint_state_interface.h>
00039 #include <hardware_interface/robot_hw.h>
00040 #include <realtime_tools/realtime_buffer.h>
00041 
00042 // NaN
00043 #include <limits>
00044 
00045 // ostringstream
00046 #include <sstream>
00047 
00048 template <unsigned int NUM_JOINTS = 2>
00049 class Diffbot : public hardware_interface::RobotHW
00050 {
00051 public:
00052   Diffbot()
00053   : running_(true)
00054   , start_srv_(nh_.advertiseService("start", &Diffbot::start_callback, this))
00055   , stop_srv_(nh_.advertiseService("stop", &Diffbot::stop_callback, this))
00056   {
00057     // Intialize raw data
00058     std::fill_n(pos_, NUM_JOINTS, 0.0);
00059     std::fill_n(vel_, NUM_JOINTS, 0.0);
00060     std::fill_n(eff_, NUM_JOINTS, 0.0);
00061     std::fill_n(cmd_, NUM_JOINTS, 0.0);
00062 
00063     // Connect and register the joint state and velocity interface
00064     for (unsigned int i = 0; i < NUM_JOINTS; ++i)
00065     {
00066       std::ostringstream os;
00067       os << "wheel_" << i << "_joint";
00068 
00069       hardware_interface::JointStateHandle state_handle(os.str(), &pos_[i], &vel_[i], &eff_[i]);
00070       jnt_state_interface_.registerHandle(state_handle);
00071 
00072       hardware_interface::JointHandle vel_handle(jnt_state_interface_.getHandle(os.str()), &cmd_[i]);
00073       jnt_vel_interface_.registerHandle(vel_handle);
00074     }
00075 
00076     registerInterface(&jnt_state_interface_);
00077     registerInterface(&jnt_vel_interface_);
00078   }
00079 
00080   ros::Time getTime() const {return ros::Time::now();}
00081   ros::Duration getPeriod() const {return ros::Duration(0.01);}
00082 
00083   void read()
00084   {
00085     std::ostringstream os;
00086     for (unsigned int i = 0; i < NUM_JOINTS - 1; ++i)
00087     {
00088       os << cmd_[i] << ", ";
00089     }
00090     os << cmd_[NUM_JOINTS - 1];
00091 
00092     ROS_INFO_STREAM("Commands for joints: " << os.str());
00093   }
00094 
00095   void write()
00096   {
00097     if (running_)
00098     {
00099       for (unsigned int i = 0; i < NUM_JOINTS; ++i)
00100       {
00101         // Note that pos_[i] will be NaN for one more cycle after we start(),
00102         // but that is consistent with the knowledge we have about the state
00103         // of the robot.
00104         pos_[i] += vel_[i]*getPeriod().toSec(); // update position
00105         vel_[i] = cmd_[i]; // might add smoothing here later
00106       }
00107     }
00108     else
00109     {
00110       std::fill_n(pos_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
00111       std::fill_n(vel_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
00112     }
00113   }
00114 
00115   bool start_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
00116   {
00117     running_ = true;
00118     return true;
00119   }
00120 
00121   bool stop_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/)
00122   {
00123     running_ = false;
00124     return true;
00125   }
00126 
00127 private:
00128   hardware_interface::JointStateInterface    jnt_state_interface_;
00129   hardware_interface::VelocityJointInterface jnt_vel_interface_;
00130   double cmd_[NUM_JOINTS];
00131   double pos_[NUM_JOINTS];
00132   double vel_[NUM_JOINTS];
00133   double eff_[NUM_JOINTS];
00134   bool running_;
00135 
00136   ros::NodeHandle nh_;
00137   ros::ServiceServer start_srv_;
00138   ros::ServiceServer stop_srv_;
00139 };


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Thu Jun 6 2019 18:58:48