armadillo2_sim_interface.h
Go to the documentation of this file.
1 
2 #ifndef ARMADILLO2_SIM_INTERFACE_ARMADILLO2_SIM_INTERFACE_H
3 #define ARMADILLO2_SIM_INTERFACE_ARMADILLO2_SIM_INTERFACE_H
4 
5 // ros_control
6 #include <control_toolbox/pid.h>
14 
15 // Gazebo
16 #include <gazebo/common/common.hh>
17 #include <gazebo/physics/physics.hh>
18 #include <gazebo/gazebo.hh>
19 
20 // ROS
21 #include <ros/ros.h>
22 #include <angles/angles.h>
24 
25 // gazebo_ros_control
27 
28 // URDF
29 #include <urdf/model.h>
30 
31 
32 namespace gazebo_ros_control {
33 
35  {
36  public:
37 
38  virtual bool initSim(
39  const std::string& robot_namespace,
40  ros::NodeHandle model_nh,
41  gazebo::physics::ModelPtr parent_model,
42  const urdf::Model *const urdf_model,
43  std::vector<transmission_interface::TransmissionInfo> transmissions);
44 
45  virtual void readSim(ros::Time time, ros::Duration period);
46 
47  virtual void writeSim(ros::Time time, ros::Duration period);
48 
49  virtual void eStopActive(const bool active);
50 
51  protected:
52  // Methods used to control a joint.
54 
55  // Register the limits of the joint specified by joint_name and joint_handle. The limits are
56  // retrieved from joint_limit_nh. If urdf_model is not NULL, limits are retrieved from it also.
57  // Return the joint's type, lower position limit, upper position limit, and effort limit.
58  void registerJointLimits(const std::string& joint_name,
59  const hardware_interface::JointHandle& joint_handle,
60  const ControlMethod ctrl_method,
61  const ros::NodeHandle& joint_limit_nh,
62  const urdf::Model *const urdf_model,
63  int *const joint_type, double *const lower_limit,
64  double *const upper_limit, double *const effort_limit);
65 
66  void registerJointLimits(const std::string& joint_name,
67  const hardware_interface::PosVelJointHandle& joint_handle,
68  const ControlMethod ctrl_method,
69  const ros::NodeHandle& joint_limit_nh,
70  const urdf::Model *const urdf_model,
71  int *const joint_type, double *const lower_limit,
72  double *const upper_limit, double *const effort_limit);
73 
74  unsigned int n_dof_;
75 
81 
88 
89 
90  std::vector<std::string> joint_names_;
91  std::vector<int> joint_types_;
92  std::vector<double> joint_lower_limits_;
93  std::vector<double> joint_upper_limits_;
94  std::vector<double> joint_effort_limits_;
95  std::vector<ControlMethod> joint_control_methods_;
96  std::vector<control_toolbox::Pid> pid_controllers_;
97  std::vector<double> joint_position_;
98  std::vector<double> joint_velocity_;
99  std::vector<double> joint_effort_;
100  std::vector<double> joint_effort_command_;
101  std::vector<double> joint_position_command_;
102  std::vector<double> last_joint_position_command_;
103  std::vector<double> joint_velocity_command_;
104 
105  std::vector<gazebo::physics::JointPtr> sim_joints_;
106 
107  // e_stop_active_ is true if the emergency stop is active.
109  };
110 
112 }
113 
114 #endif //ARMADILLO2_SIM_INTERFACE_ARMADILLO2_SIM_INTERFACE_H
hardware_interface::PosVelJointInterface pvj_interface_
hardware_interface::PositionJointInterface pj_interface_
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_
boost::shared_ptr< DefaultRobotHWSim > DefaultRobotHWSimPtr
virtual void readSim(ros::Time time, ros::Duration period)
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
std::vector< ControlMethod > joint_control_methods_
joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
hardware_interface::JointStateInterface js_interface_
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)
virtual void writeSim(ros::Time time, ros::Duration period)
hardware_interface::VelocityJointInterface vj_interface_
hardware_interface::EffortJointInterface ej_interface_
joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_
std::vector< gazebo::physics::JointPtr > sim_joints_
std::vector< control_toolbox::Pid > pid_controllers_
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)
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_


armadillo2_sim_interface
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Wed Jan 3 2018 03:47:52