default_robot_hw_sim.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Open Source Robotics Foundation
5  * Copyright (c) 2013, The Johns Hopkins University
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Open Source Robotics Foundation
19  * nor the names of its contributors may be
20  * used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /* Author: Dave Coleman, Jonathan Bohren
38  Desc: Hardware Interface for any simulated robot in Gazebo
39 */
40 
41 #ifndef _GAZEBO_ROS_CONTROL___DEFAULT_ROBOT_HW_SIM_H_
42 #define _GAZEBO_ROS_CONTROL___DEFAULT_ROBOT_HW_SIM_H_
43 
44 // ros_control
45 #include <control_toolbox/pid.h>
52 
53 // Gazebo
54 #include <gazebo/common/common.hh>
55 #include <gazebo/physics/physics.hh>
56 #include <gazebo/gazebo.hh>
57 
58 // ROS
59 #include <ros/ros.h>
60 #include <angles/angles.h>
62 
63 // gazebo_ros_control
65 
66 // URDF
67 #include <urdf/model.h>
68 
69 
70 
72 {
73 
75 {
76 public:
77 
78  virtual bool initSim(
79  const std::string& robot_namespace,
80  ros::NodeHandle model_nh,
81  gazebo::physics::ModelPtr parent_model,
82  const urdf::Model *const urdf_model,
83  std::vector<transmission_interface::TransmissionInfo> transmissions);
84 
85  virtual void readSim(ros::Time time, ros::Duration period);
86 
87  virtual void writeSim(ros::Time time, ros::Duration period);
88 
89  virtual void eStopActive(const bool active);
90 
91 protected:
92  // Methods used to control a joint.
94 
95  // Register the limits of the joint specified by joint_name and joint_handle. The limits are
96  // retrieved from joint_limit_nh. If urdf_model is not NULL, limits are retrieved from it also.
97  // Return the joint's type, lower position limit, upper position limit, and effort limit.
98  void registerJointLimits(const std::string& joint_name,
99  const hardware_interface::JointHandle& joint_handle,
100  const ControlMethod ctrl_method,
101  const ros::NodeHandle& joint_limit_nh,
102  const urdf::Model *const urdf_model,
103  int *const joint_type, double *const lower_limit,
104  double *const upper_limit, double *const effort_limit);
105 
106  unsigned int n_dof_;
107 
112 
119 
120  std::vector<std::string> joint_names_;
121  std::vector<int> joint_types_;
122  std::vector<double> joint_lower_limits_;
123  std::vector<double> joint_upper_limits_;
124  std::vector<double> joint_effort_limits_;
125  std::vector<ControlMethod> joint_control_methods_;
126  std::vector<control_toolbox::Pid> pid_controllers_;
127  std::vector<double> joint_position_;
128  std::vector<double> joint_velocity_;
129  std::vector<double> joint_effort_;
130  std::vector<double> joint_effort_command_;
131  std::vector<double> joint_position_command_;
132  std::vector<double> last_joint_position_command_;
133  std::vector<double> joint_velocity_command_;
134 
135  std::vector<gazebo::physics::JointPtr> sim_joints_;
136 
137  std::string physics_type_;
138 
139  // e_stop_active_ is true if the emergency stop is active.
141 };
142 
144 
145 }
146 
147 #endif // #ifndef __GAZEBO_ROS_CONTROL_PLUGIN_DEFAULT_ROBOT_HW_SIM_H_
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
hardware_interface::PositionJointInterface pj_interface_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
boost::shared_ptr< DefaultRobotHWSim > DefaultRobotHWSimPtr
virtual void readSim(ros::Time time, ros::Duration period)
Read state data from the simulated robot hardware.
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_
joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_
hardware_interface::VelocityJointInterface vj_interface_
std::vector< control_toolbox::Pid > pid_controllers_
virtual void eStopActive(const bool active)
Set the emergency stop state.
hardware_interface::JointStateInterface js_interface_
hardware_interface::EffortJointInterface ej_interface_
std::vector< gazebo::physics::JointPtr > sim_joints_
virtual void writeSim(ros::Time time, ros::Duration period)
Write commands to the simulated robot hardware.
std::vector< ControlMethod > joint_control_methods_
void registerJointLimits(const std::string &joint_name, const hardware_interface::JointHandle &joint_handle, const ControlMethod ctrl_method, const ros::NodeHandle &joint_limit_nh, const urdf::Model *const urdf_model, int *const joint_type, double *const lower_limit, double *const upper_limit, double *const effort_limit)
std::vector< double > last_joint_position_command_
virtual bool initSim(const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *const urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions)
Initialize the simulated robot hardware.
Gazebo plugin version of RobotHW.
Definition: robot_hw_sim.h:68
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_
Plugin template for hardware interfaces for ros_control and Gazebo.
joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_


gazebo_ros_control
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Tue Mar 26 2019 02:31:37