ros_control_interface.hpp
Go to the documentation of this file.
00001 #ifndef __ROS_CONTROL_INTERFACE__
00002 #define __ROS_CONTROL_INTERFACE__
00003 
00004 #include <controller_interface/controller.h>
00005 #include <hardware_interface/joint_command_interface.h>
00006 #include <urdf/model.h>
00007 #include <generic_control_toolbox/controller_template.hpp>
00008 
00009 namespace generic_control_toolbox
00010 {
00011 enum JointType
00012 {
00013   EFFORT,
00014   VELOCITY,
00015   POSITION
00016 };
00017 
00021 template <class JointInterface>
00022 class RosControlInterface
00023     : public controller_interface::Controller<JointInterface>
00024 {
00025  public:
00026   RosControlInterface();
00027 
00028   bool init(JointInterface* hw, ros::NodeHandle& nh);
00029   void starting(const ros::Time& time);
00030   void update(const ros::Time& time, const ros::Duration& period);
00031   void stopping(const ros::Time& time);
00032 
00033  protected:
00042   virtual std::shared_ptr<ControllerBase> initController(
00043       ros::NodeHandle& nh) const = 0;
00044 
00045  private:
00046   std::shared_ptr<ControllerBase> controller_;
00047   JointType joint_type_;
00048   unsigned int n_joints_;
00049   std::vector<std::string> joint_names_;
00050   std::vector<urdf::JointConstSharedPtr> joint_urdfs_;
00051   std::vector<hardware_interface::JointHandle> joints_;
00052 };
00053 
00054 // Implementation in header file due to being a template class.
00055 
00056 template <class JointInterface>
00057 RosControlInterface<JointInterface>::RosControlInterface()
00058 {
00059   controller_ = NULL;
00060 
00061   // check interface type
00062   JointInterface* hw = new JointInterface();
00063   if (hardware_interface::EffortJointInterface* j =
00064           dynamic_cast<hardware_interface::EffortJointInterface*>(hw))
00065   {
00066     joint_type_ = EFFORT;
00067   }
00068   else if (hardware_interface::VelocityJointInterface* j =
00069                dynamic_cast<hardware_interface::VelocityJointInterface*>(hw))
00070   {
00071     joint_type_ = VELOCITY;
00072   }
00073   else if (hardware_interface::PositionJointInterface* j =
00074                dynamic_cast<hardware_interface::PositionJointInterface*>(hw))
00075   {
00076     joint_type_ = POSITION;
00077   }
00078   else
00079   {
00080     throw std::logic_error("UNKNOWN JOINT INTERFACE TYPE");
00081   }
00082 }
00083 
00084 template <class JointInterface>
00085 bool RosControlInterface<JointInterface>::init(JointInterface* hw,
00086                                                ros::NodeHandle& nh)
00087 {
00088   controller_ = initController(nh);
00089   if (!controller_)
00090   {
00091     ROS_ERROR_STREAM("Failed to initialize controller algorithm! (namespace: "
00092                      << nh.getNamespace() << ").");
00093   }
00094 
00095   // joint initialization from
00096   // https://github.com/ros-controls/ros_controllers/blob/melodic-devel/effort_controllers/src/joint_group_position_controller.cpp
00097 
00098   joint_names_ = hw->getNames();
00099   n_joints_ = joint_names_.size();
00100 
00101   // Get URDF
00102   urdf::Model urdf;
00103   if (!urdf.initParam("robot_description"))
00104   {
00105     ROS_ERROR("Failed to parse urdf file");
00106     return false;
00107   }
00108 
00109   for (unsigned int i = 0; i < n_joints_; i++)
00110   {
00111     const std::string& name = joint_names_[i];
00112 
00113     try
00114     {
00115       joints_.push_back(hw->getHandle(name));
00116     }
00117     catch (const hardware_interface::HardwareInterfaceException& e)
00118     {
00119       ROS_ERROR_STREAM("Exception: " << e.what());
00120     }
00121 
00122     urdf::JointConstSharedPtr joint_urdf = urdf.getJoint(name);
00123     if (!joint_urdf)
00124     {
00125       ROS_ERROR("Could not find joint '%s' in urdf", name.c_str());
00126       return false;
00127     }
00128     joint_urdfs_.push_back(joint_urdf);
00129   }
00130 
00131   controller_->resetInternalState();
00132 }
00133 
00134 template <class JointInterface>
00135 void RosControlInterface<JointInterface>::starting(const ros::Time& time)
00136 {
00137   controller_->resetInternalState();
00138 }
00139 
00140 template <class JointInterface>
00141 void RosControlInterface<JointInterface>::update(const ros::Time& time,
00142                                                  const ros::Duration& period)
00143 {
00144   sensor_msgs::JointState curr_state, command;
00145 
00146   for (unsigned int i = 0; i < n_joints_; i++)
00147   {
00148     curr_state.name.push_back(joint_names_[i]);
00149     curr_state.position.push_back(joints_[i].getPosition());
00150     curr_state.velocity.push_back(joints_[i].getVelocity());
00151     curr_state.effort.push_back(joints_[i].getEffort());
00152   }
00153 
00154   command = controller_->updateControl(curr_state, period);
00155 
00156   for (unsigned int i = 0; i < n_joints_; i++)
00157   {
00158     const std::string& name = joint_names_[i];
00159 
00160     for (unsigned int j = 0; j < command.name.size(); j++)
00161     {
00162       if (command.name[j] == name)
00163       {
00164         switch (joint_type_)
00165         {
00166           case EFFORT:
00167             joints_[i].setCommand(command.effort[j]);
00168             break;
00169           case VELOCITY:
00170             joints_[i].setCommand(command.velocity[j]);
00171             break;
00172           case POSITION:
00173             joints_[i].setCommand(command.position[j]);
00174             break;
00175         }
00176       }
00177     }
00178   }
00179 }
00180 
00181 template <class JointInterface>
00182 void RosControlInterface<JointInterface>::stopping(const ros::Time& time)
00183 {
00184   controller_->resetInternalState();
00185 }
00186 }  // namespace generic_control_toolbox
00187 #endif


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 18:02:57