generic_hw_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, University of Colorado, Boulder
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 the Univ of CO, Boulder 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: Example ros_control hardware interface that performs a perfect control loop for
37  simulation
38 */
39 
40 #ifndef GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H
41 #define GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H
42 
43 // C++
44 #include <boost/scoped_ptr.hpp>
45 
46 // ROS
47 #include <ros/ros.h>
48 #include <urdf/model.h>
49 
50 // ROS Controls
59 
61 {
62 
65 {
66 public:
72  GenericHWInterface(const ros::NodeHandle &nh, urdf::Model *urdf_model = NULL);
73 
75  virtual ~GenericHWInterface() {}
76 
78  virtual void init();
79 
81  virtual void read(ros::Duration &elapsed_time) = 0;
82 
90  virtual void read(const ros::Time& /*time*/, const ros::Duration& period) override
91  {
92  ros::Duration elapsed_time = period;
93  read(elapsed_time);
94  }
95 
97  virtual void write(ros::Duration &elapsed_time) = 0;
98 
106  virtual void write(const ros::Time& /*time*/, const ros::Duration& period) override
107  {
108  ros::Duration elapsed_time = period;
109  write(elapsed_time);
110  }
111 
113  virtual void reset();
114 
121  virtual bool canSwitch(const std::list<hardware_interface::ControllerInfo> &start_list,
122  const std::list<hardware_interface::ControllerInfo> &stop_list) const
123  {
124  return true;
125  }
126 
132  virtual void doSwitch(const std::list<hardware_interface::ControllerInfo> &start_list,
133  const std::list<hardware_interface::ControllerInfo> &stop_list)
134  {
135  }
136 
143  virtual void registerJointLimits(const hardware_interface::JointHandle &joint_handle_position,
144  const hardware_interface::JointHandle &joint_handle_velocity,
145  const hardware_interface::JointHandle &joint_handle_effort,
146  std::size_t joint_id);
147 
149  virtual void enforceLimits(ros::Duration &period) = 0;
150 
152  virtual void printState();
153  std::string printStateHelper();
154 
156  std::string printCommandHelper();
157 
158 protected:
159 
161  virtual void loadURDF(const ros::NodeHandle& nh, std::string param_name);
162 
163  // Short name of this class
164  std::string name_;
165 
166  // Startup and shutdown of the internal node inside a roscpp program
168 
169  // Hardware interfaces
174 
175  // Joint limits interfaces - Saturation
179 
180  // Joint limits interfaces - Soft limits
184 
185  // Configuration
186  std::vector<std::string> joint_names_;
187  std::size_t num_joints_;
189 
190  // Modes
193 
194  // States
195  std::vector<double> joint_position_;
196  std::vector<double> joint_velocity_;
197  std::vector<double> joint_effort_;
198 
199  // Commands
200  std::vector<double> joint_position_command_;
201  std::vector<double> joint_velocity_command_;
202  std::vector<double> joint_effort_command_;
203 
204  // Copy of limits, in case we need them later in our control stack
205  std::vector<double> joint_position_lower_limits_;
206  std::vector<double> joint_position_upper_limits_;
207  std::vector<double> joint_velocity_limits_;
208  std::vector<double> joint_effort_limits_;
209 
210 }; // class
211 
212 } // namespace
213 
214 #endif // GENERIC_ROS_CONTROL_GENERIC_HW_INTERFACE_H
hardware_interface::EffortJointInterface effort_joint_interface_
virtual void write(const ros::Time &, const ros::Duration &period) override
Write the command to the robot hardware.
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
Perform (in non-realtime) all necessary hardware interface switches in order to start and stop the gi...
virtual void read(ros::Duration &elapsed_time)=0
Read the state from the robot hardware.
hardware_interface::JointStateInterface joint_state_interface_
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_
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_
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.
virtual void write(ros::Duration &elapsed_time)=0
Write the command to the robot hardware.
GenericHWInterface(const ros::NodeHandle &nh, urdf::Model *urdf_model=NULL)
Constructor.
virtual bool canSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) const
Check (in non-realtime) if given controllers could be started and stopped from the current state of t...
virtual void loadURDF(const ros::NodeHandle &nh, std::string param_name)
Get the URDF XML from the parameter server.
virtual void read(const ros::Time &, const ros::Duration &period) override
Read the state from the robot hardware.
joint_limits_interface::VelocityJointSoftLimitsInterface vel_jnt_soft_limits_
hardware_interface::PositionJointInterface position_joint_interface_
virtual void enforceLimits(ros::Duration &period)=0
joint_limits_interface::PositionJointSaturationInterface pos_jnt_sat_interface_


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Thu Feb 25 2021 03:58:54