generic_hw_interface.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, University of Colorado, Boulder
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Univ of CO, Boulder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman
00036    Desc:   Example ros_control hardware interface that performs a perfect control loop for
00037    simulation
00038 */
00039 
00040 #ifndef GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H
00041 #define GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H
00042 
00043 // C++
00044 #include <boost/scoped_ptr.hpp>
00045 
00046 // ROS
00047 #include <ros/ros.h>
00048 #include <urdf/model.h>
00049 
00050 // ROS Controls
00051 #include <hardware_interface/robot_hw.h>
00052 #include <hardware_interface/joint_state_interface.h>
00053 #include <hardware_interface/joint_command_interface.h>
00054 #include <controller_manager/controller_manager.h>
00055 #include <joint_limits_interface/joint_limits.h>
00056 #include <joint_limits_interface/joint_limits_interface.h>
00057 #include <joint_limits_interface/joint_limits_rosparam.h>
00058 #include <joint_limits_interface/joint_limits_urdf.h>
00059 
00060 namespace ros_control_boilerplate
00061 {
00062 
00064 class GenericHWInterface : public hardware_interface::RobotHW
00065 {
00066 public:
00072   GenericHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model = NULL);
00073 
00075   virtual ~GenericHWInterface() {}
00076 
00078   virtual void init();
00079 
00081   virtual void read(ros::Duration &elapsed_time) = 0;
00082 
00084   virtual void write(ros::Duration &elapsed_time) = 0;
00085 
00087   virtual void reset();
00088 
00095   virtual bool canSwitch(const std::list<hardware_interface::ControllerInfo> &start_list,
00096                          const std::list<hardware_interface::ControllerInfo> &stop_list) const
00097   {
00098     return true;
00099   }
00100 
00106   virtual void doSwitch(const std::list<hardware_interface::ControllerInfo> &start_list,
00107                         const std::list<hardware_interface::ControllerInfo> &stop_list)
00108   {
00109   }
00110 
00117   virtual void registerJointLimits(const hardware_interface::JointHandle &joint_handle_position,
00118                            const hardware_interface::JointHandle &joint_handle_velocity,
00119                            const hardware_interface::JointHandle &joint_handle_effort,
00120                            std::size_t joint_id);
00121 
00123   virtual void enforceLimits(ros::Duration &period) = 0;
00124 
00126   virtual void printState();
00127   std::string printStateHelper();
00128 
00130   std::string printCommandHelper();
00131 
00132 protected:
00133 
00135   virtual void loadURDF(ros::NodeHandle& nh, std::string param_name);
00136 
00137   // Short name of this class
00138   std::string name_;
00139 
00140   // Startup and shutdown of the internal node inside a roscpp program
00141   ros::NodeHandle nh_;
00142 
00143   // Hardware interfaces
00144   hardware_interface::JointStateInterface joint_state_interface_;
00145   hardware_interface::PositionJointInterface position_joint_interface_;
00146   hardware_interface::VelocityJointInterface velocity_joint_interface_;
00147   hardware_interface::EffortJointInterface effort_joint_interface_;
00148 
00149   // Joint limits interfaces - Saturation
00150   joint_limits_interface::PositionJointSaturationInterface pos_jnt_sat_interface_;
00151   joint_limits_interface::VelocityJointSaturationInterface vel_jnt_sat_interface_;
00152   joint_limits_interface::EffortJointSaturationInterface eff_jnt_sat_interface_;
00153 
00154   // Joint limits interfaces - Soft limits
00155   joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_soft_limits_;
00156   joint_limits_interface::VelocityJointSoftLimitsInterface vel_jnt_soft_limits_;
00157   joint_limits_interface::EffortJointSoftLimitsInterface eff_jnt_soft_limits_;
00158 
00159   // Configuration
00160   std::vector<std::string> joint_names_;
00161   std::size_t num_joints_;
00162   urdf::Model *urdf_model_;
00163 
00164   // Modes
00165   bool use_rosparam_joint_limits_;
00166   bool use_soft_limits_if_available_;
00167 
00168   // States
00169   std::vector<double> joint_position_;
00170   std::vector<double> joint_velocity_;
00171   std::vector<double> joint_effort_;
00172 
00173   // Commands
00174   std::vector<double> joint_position_command_;
00175   std::vector<double> joint_velocity_command_;
00176   std::vector<double> joint_effort_command_;
00177 
00178   // Copy of limits, in case we need them later in our control stack
00179   std::vector<double> joint_position_lower_limits_;
00180   std::vector<double> joint_position_upper_limits_;
00181   std::vector<double> joint_velocity_limits_;
00182   std::vector<double> joint_effort_limits_;
00183 
00184 };  // class
00185 
00186 }  // namespace
00187 
00188 #endif // GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Thu Jun 6 2019 20:37:19