ros_control_interface.hpp
Go to the documentation of this file.
1 #ifndef __ROS_CONTROL_INTERFACE__
2 #define __ROS_CONTROL_INTERFACE__
3 
6 #include <urdf/model.h>
8 
10 {
12 {
16 };
17 
21 template <class JointInterface>
23  : public controller_interface::Controller<JointInterface>
24 {
25  public:
27 
28  bool init(JointInterface* hw, ros::NodeHandle& nh);
29  void starting(const ros::Time& time);
30  void update(const ros::Time& time, const ros::Duration& period);
31  void stopping(const ros::Time& time);
32 
33  protected:
42  virtual std::shared_ptr<ControllerBase> initController(
43  ros::NodeHandle& nh) const = 0;
44 
45  private:
46  std::shared_ptr<ControllerBase> controller_;
48  unsigned int n_joints_;
49  std::vector<std::string> joint_names_;
50  std::vector<urdf::JointConstSharedPtr> joint_urdfs_;
51  std::vector<hardware_interface::JointHandle> joints_;
52 };
53 
54 // Implementation in header file due to being a template class.
55 
56 template <class JointInterface>
58 {
59  controller_ = NULL;
60 
61  // check interface type
62  JointInterface* hw = new JointInterface();
64  dynamic_cast<hardware_interface::EffortJointInterface*>(hw))
65  {
67  }
69  dynamic_cast<hardware_interface::VelocityJointInterface*>(hw))
70  {
72  }
74  dynamic_cast<hardware_interface::PositionJointInterface*>(hw))
75  {
77  }
78  else
79  {
80  throw std::logic_error("UNKNOWN JOINT INTERFACE TYPE");
81  }
82 }
83 
84 template <class JointInterface>
86  ros::NodeHandle& nh)
87 {
89  if (!controller_)
90  {
91  ROS_ERROR_STREAM("Failed to initialize controller algorithm! (namespace: "
92  << nh.getNamespace() << ").");
93  }
94 
95  // joint initialization from
96  // https://github.com/ros-controls/ros_controllers/blob/melodic-devel/effort_controllers/src/joint_group_position_controller.cpp
97 
98  joint_names_ = hw->getNames();
99  n_joints_ = joint_names_.size();
100 
101  // Get URDF
103  if (!urdf.initParam("robot_description"))
104  {
105  ROS_ERROR("Failed to parse urdf file");
106  return false;
107  }
108 
109  for (unsigned int i = 0; i < n_joints_; i++)
110  {
111  const std::string& name = joint_names_[i];
112 
113  try
114  {
115  joints_.push_back(hw->getHandle(name));
116  }
118  {
119  ROS_ERROR_STREAM("Exception: " << e.what());
120  }
121 
122  urdf::JointConstSharedPtr joint_urdf = urdf.getJoint(name);
123  if (!joint_urdf)
124  {
125  ROS_ERROR("Could not find joint '%s' in urdf", name.c_str());
126  return false;
127  }
128  joint_urdfs_.push_back(joint_urdf);
129  }
130 
131  controller_->resetInternalState();
132 }
133 
134 template <class JointInterface>
136 {
137  controller_->resetInternalState();
138 }
139 
140 template <class JointInterface>
142  const ros::Duration& period)
143 {
144  sensor_msgs::JointState curr_state, command;
145 
146  for (unsigned int i = 0; i < n_joints_; i++)
147  {
148  curr_state.name.push_back(joint_names_[i]);
149  curr_state.position.push_back(joints_[i].getPosition());
150  curr_state.velocity.push_back(joints_[i].getVelocity());
151  curr_state.effort.push_back(joints_[i].getEffort());
152  }
153 
154  command = controller_->updateControl(curr_state, period);
155 
156  for (unsigned int i = 0; i < n_joints_; i++)
157  {
158  const std::string& name = joint_names_[i];
159 
160  for (unsigned int j = 0; j < command.name.size(); j++)
161  {
162  if (command.name[j] == name)
163  {
164  switch (joint_type_)
165  {
166  case EFFORT:
167  joints_[i].setCommand(command.effort[j]);
168  break;
169  case VELOCITY:
170  joints_[i].setCommand(command.velocity[j]);
171  break;
172  case POSITION:
173  joints_[i].setCommand(command.position[j]);
174  break;
175  }
176  }
177  }
178  }
179 }
180 
181 template <class JointInterface>
183 {
184  controller_->resetInternalState();
185 }
186 } // namespace generic_control_toolbox
187 #endif
ROSLIB_DECL std::string command(const std::string &cmd)
bool init(JointInterface *hw, ros::NodeHandle &nh)
const std::string & getNamespace() const
void update(const ros::Time &time, const ros::Duration &period)
URDF_EXPORT bool initParam(const std::string &param)
std::vector< urdf::JointConstSharedPtr > joint_urdfs_
virtual std::shared_ptr< ControllerBase > initController(ros::NodeHandle &nh) const =0
std::vector< hardware_interface::JointHandle > joints_
#define ROS_ERROR_STREAM(args)
std::shared_ptr< ControllerBase > controller_
#define ROS_ERROR(...)


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 19:54:44