generic_hw_interface.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, PickNik LLC
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik LLC nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman
36  Desc: Helper ros_control hardware interface that loads configurations
37 */
38 
40 #include <limits>
41 
42 // ROS parameter loading
44 
46 {
48  : name_("generic_hw_interface"), nh_(nh), use_rosparam_joint_limits_(false), use_soft_limits_if_available_(false)
49 {
50  // Check if the URDF model needs to be loaded
51  if (urdf_model == NULL)
52  loadURDF(nh, "robot_description");
53  else
54  urdf_model_ = urdf_model;
55 
56  // Load rosparams
57  ros::NodeHandle rpnh(
58  nh_, "hardware_interface"); // TODO(davetcoleman): change the namespace to "generic_hw_interface" aka name_
59  std::size_t error = 0;
60  error += !rosparam_shortcuts::get(name_, rpnh, "joints", joint_names_);
62 }
63 
65 {
66  num_joints_ = joint_names_.size();
67 
68  // Status
69  joint_position_.resize(num_joints_, 0.0);
70  joint_velocity_.resize(num_joints_, 0.0);
71  joint_effort_.resize(num_joints_, 0.0);
72 
73  // Command
77 
78  // Limits
82  joint_effort_limits_.resize(num_joints_, 0.0);
83 
84  // Initialize interfaces for each joint
85  for (std::size_t joint_id = 0; joint_id < num_joints_; ++joint_id)
86  {
87  ROS_DEBUG_STREAM_NAMED(name_, "Loading joint name: " << joint_names_[joint_id]);
88 
89  // Create joint state interface
91  joint_names_[joint_id], &joint_position_[joint_id], &joint_velocity_[joint_id], &joint_effort_[joint_id]));
92 
93  // Add command interfaces to joints
94  // TODO: decide based on transmissions?
97  position_joint_interface_.registerHandle(joint_handle_position);
98 
101  velocity_joint_interface_.registerHandle(joint_handle_velocity);
102 
105  effort_joint_interface_.registerHandle(joint_handle_effort);
106 
107  // Load the joint limits
108  registerJointLimits(joint_handle_position, joint_handle_velocity, joint_handle_effort, joint_id);
109  } // end for each joint
110 
111  registerInterface(&joint_state_interface_); // From RobotHW base class.
112  registerInterface(&position_joint_interface_); // From RobotHW base class.
113  registerInterface(&velocity_joint_interface_); // From RobotHW base class.
114  registerInterface(&effort_joint_interface_); // From RobotHW base class.
115 
116  ROS_INFO_STREAM_NAMED(name_, "GenericHWInterface Ready.");
117 }
118 
120  const hardware_interface::JointHandle& joint_handle_velocity,
121  const hardware_interface::JointHandle& joint_handle_effort,
122  std::size_t joint_id)
123 {
124  // Default values
125  joint_position_lower_limits_[joint_id] = -std::numeric_limits<double>::max();
126  joint_position_upper_limits_[joint_id] = std::numeric_limits<double>::max();
127  joint_velocity_limits_[joint_id] = std::numeric_limits<double>::max();
128  joint_effort_limits_[joint_id] = std::numeric_limits<double>::max();
129 
130  // Limits datastructures
131  joint_limits_interface::JointLimits joint_limits; // Position
132  joint_limits_interface::SoftJointLimits soft_limits; // Soft Position
133  bool has_joint_limits = false;
134  bool has_soft_limits = false;
135 
136  // Get limits from URDF
137  if (urdf_model_ == NULL)
138  {
139  ROS_WARN_STREAM_NAMED(name_, "No URDF model loaded, unable to get joint limits");
140  return;
141  }
142 
143  // Get limits from URDF
144  urdf::JointConstSharedPtr urdf_joint = urdf_model_->getJoint(joint_names_[joint_id]);
145 
146  // Get main joint limits
147  if (urdf_joint == NULL)
148  {
149  ROS_ERROR_STREAM_NAMED(name_, "URDF joint not found " << joint_names_[joint_id]);
150  return;
151  }
152 
153  // Get limits from URDF
154  if (joint_limits_interface::getJointLimits(urdf_joint, joint_limits))
155  {
156  has_joint_limits = true;
157  ROS_DEBUG_STREAM_NAMED(name_, "Joint " << joint_names_[joint_id] << " has URDF position limits ["
158  << joint_limits.min_position << ", " << joint_limits.max_position << "]");
159  if (joint_limits.has_velocity_limits)
160  ROS_DEBUG_STREAM_NAMED(name_, "Joint " << joint_names_[joint_id] << " has URDF velocity limit ["
161  << joint_limits.max_velocity << "]");
162  }
163  else
164  {
165  if (urdf_joint->type != urdf::Joint::CONTINUOUS)
166  ROS_WARN_STREAM_NAMED(name_, "Joint " << joint_names_[joint_id]
167  << " does not have a URDF "
168  "position limit");
169  }
170 
171  // Get limits from ROS param
173  {
174  if (joint_limits_interface::getJointLimits(joint_names_[joint_id], nh_, joint_limits))
175  {
176  has_joint_limits = true;
177  ROS_DEBUG_STREAM_NAMED(name_, "Joint " << joint_names_[joint_id] << " has rosparam position limits ["
178  << joint_limits.min_position << ", " << joint_limits.max_position << "]");
179  if (joint_limits.has_velocity_limits)
180  ROS_DEBUG_STREAM_NAMED(name_, "Joint " << joint_names_[joint_id] << " has rosparam velocity limit ["
181  << joint_limits.max_velocity << "]");
182  } // the else debug message provided internally by joint_limits_interface
183  }
184 
185  // Get soft limits from URDF
187  {
188  if (joint_limits_interface::getSoftJointLimits(urdf_joint, soft_limits))
189  {
190  has_soft_limits = true;
191  ROS_DEBUG_STREAM_NAMED(name_, "Joint " << joint_names_[joint_id] << " has soft joint limits.");
192  }
193  else
194  {
195  ROS_DEBUG_STREAM_NAMED(name_, "Joint " << joint_names_[joint_id]
196  << " does not have soft joint "
197  "limits");
198  }
199  }
200 
201  // Quit we we haven't found any limits in URDF or rosparam server
202  if (!has_joint_limits)
203  {
204  return;
205  }
206 
207  // Copy position limits if available
208  if (joint_limits.has_position_limits)
209  {
210  // Slighly reduce the joint limits to prevent floating point errors
211  joint_limits.min_position += std::numeric_limits<double>::epsilon();
212  joint_limits.max_position -= std::numeric_limits<double>::epsilon();
213 
214  joint_position_lower_limits_[joint_id] = joint_limits.min_position;
215  joint_position_upper_limits_[joint_id] = joint_limits.max_position;
216  }
217 
218  // Copy velocity limits if available
219  if (joint_limits.has_velocity_limits)
220  {
221  joint_velocity_limits_[joint_id] = joint_limits.max_velocity;
222  }
223 
224  // Copy effort limits if available
225  if (joint_limits.has_effort_limits)
226  {
227  joint_effort_limits_[joint_id] = joint_limits.max_effort;
228  }
229 
230  if (has_soft_limits) // Use soft limits
231  {
232  ROS_DEBUG_STREAM_NAMED(name_, "Using soft saturation limits");
233  const joint_limits_interface::PositionJointSoftLimitsHandle soft_handle_position(joint_handle_position,
234  joint_limits, soft_limits);
235  pos_jnt_soft_limits_.registerHandle(soft_handle_position);
236  const joint_limits_interface::VelocityJointSoftLimitsHandle soft_handle_velocity(joint_handle_velocity,
237  joint_limits, soft_limits);
238  vel_jnt_soft_limits_.registerHandle(soft_handle_velocity);
239  const joint_limits_interface::EffortJointSoftLimitsHandle soft_handle_effort(joint_handle_effort, joint_limits,
240  soft_limits);
241  eff_jnt_soft_limits_.registerHandle(soft_handle_effort);
242  }
243  else // Use saturation limits
244  {
245  ROS_DEBUG_STREAM_NAMED(name_, "Using saturation limits (not soft limits)");
246 
247  const joint_limits_interface::PositionJointSaturationHandle sat_handle_position(joint_handle_position, joint_limits);
248  pos_jnt_sat_interface_.registerHandle(sat_handle_position);
249 
250  const joint_limits_interface::VelocityJointSaturationHandle sat_handle_velocity(joint_handle_velocity, joint_limits);
251  vel_jnt_sat_interface_.registerHandle(sat_handle_velocity);
252 
253  const joint_limits_interface::EffortJointSaturationHandle sat_handle_effort(joint_handle_effort, joint_limits);
254  eff_jnt_sat_interface_.registerHandle(sat_handle_effort);
255  }
256 }
257 
259 {
260  // Reset joint limits state, in case of mode switch or e-stop
263 }
264 
266 {
267  // WARNING: THIS IS NOT REALTIME SAFE
268  // FOR DEBUGGING ONLY, USE AT YOUR OWN ROBOT's RISK!
269  ROS_INFO_STREAM_THROTTLE(1, std::endl << printStateHelper());
270 }
271 
273 {
274  std::stringstream ss;
275  std::cout.precision(15);
276 
277  for (std::size_t i = 0; i < num_joints_; ++i)
278  {
279  ss << "j" << i << ": " << std::fixed << joint_position_[i] << "\t ";
280  ss << std::fixed << joint_velocity_[i] << "\t ";
281  ss << std::fixed << joint_effort_[i] << std::endl;
282  }
283  return ss.str();
284 }
285 
287 {
288  std::stringstream ss;
289  std::cout.precision(15);
290  ss << " position velocity effort \n";
291  for (std::size_t i = 0; i < num_joints_; ++i)
292  {
293  ss << "j" << i << ": " << std::fixed << joint_position_command_[i] << "\t ";
294  ss << std::fixed << joint_velocity_command_[i] << "\t ";
295  ss << std::fixed << joint_effort_command_[i] << std::endl;
296  }
297  return ss.str();
298 }
299 
300 void GenericHWInterface::loadURDF(const ros::NodeHandle& nh, std::string param_name)
301 {
302  std::string urdf_string;
303  urdf_model_ = new urdf::Model();
304 
305  // search and wait for robot_description on param server
306  while (urdf_string.empty() && ros::ok())
307  {
308  std::string search_param_name;
309  if (nh.searchParam(param_name, search_param_name))
310  {
311  ROS_INFO_STREAM_NAMED(name_, "Waiting for model URDF on the ROS param server at location: " << nh.getNamespace()
312  << search_param_name);
313  nh.getParam(search_param_name, urdf_string);
314  }
315  else
316  {
317  ROS_INFO_STREAM_NAMED(name_, "Waiting for model URDF on the ROS param server at location: " << nh.getNamespace()
318  << param_name);
319  nh.getParam(param_name, urdf_string);
320  }
321 
322  usleep(100000);
323  }
324 
325  if (!urdf_model_->initString(urdf_string))
326  ROS_ERROR_STREAM_NAMED(name_, "Unable to load URDF model");
327  else
328  ROS_DEBUG_STREAM_NAMED(name_, "Received URDF from param server");
329 }
330 
331 } // namespace ros_control_boilerplate
hardware_interface::EffortJointInterface effort_joint_interface_
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
URDF_EXPORT bool initString(const std::string &xmlstring)
hardware_interface::JointStateInterface joint_state_interface_
#define ROS_INFO_STREAM_THROTTLE(period, args)
#define ROS_INFO_STREAM_NAMED(name, args)
joint_limits_interface::EffortJointSaturationInterface eff_jnt_sat_interface_
virtual void init()
Initialize the hardware interface.
virtual void registerJointLimits(const hardware_interface::JointHandle &joint_handle_position, const hardware_interface::JointHandle &joint_handle_velocity, const hardware_interface::JointHandle &joint_handle_effort, std::size_t joint_id)
Register the limits of the joint specified by joint_id and joint_handle. The limits are retrieved fro...
joint_limits_interface::VelocityJointSaturationInterface vel_jnt_sat_interface_
bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
bool getParam(const std::string &key, std::string &s) const
virtual void printState()
Helper for debugging a joint&#39;s state.
hardware_interface::VelocityJointInterface velocity_joint_interface_
joint_limits_interface::EffortJointSoftLimitsInterface eff_jnt_soft_limits_
ROSCPP_DECL bool ok()
joint_limits_interface::PositionJointSoftLimitsInterface pos_jnt_soft_limits_
virtual void reset()
Set all members to default values.
std::string printCommandHelper()
Helper for debugging a joint&#39;s command.
void registerHandle(const JointStateHandle &handle)
bool searchParam(const std::string &key, std::string &result) const
JointStateHandle getHandle(const std::string &name)
GenericHWInterface(const ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor.
virtual void loadURDF(const ros::NodeHandle &nh, std::string param_name)
Get the URDF XML from the parameter server.
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
const std::string & getNamespace() const
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
joint_limits_interface::VelocityJointSoftLimitsInterface vel_jnt_soft_limits_
bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string &param_name, bool &value)
hardware_interface::PositionJointInterface position_joint_interface_
joint_limits_interface::PositionJointSaturationInterface pos_jnt_sat_interface_
#define ROS_WARN_STREAM_NAMED(name, args)


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Mon Feb 28 2022 23:27:26