Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
gazebo_ros_control::DefaultRobotHWSim Class Reference

#include <default_robot_hw_sim.h>

Inheritance diagram for gazebo_ros_control::DefaultRobotHWSim:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void eStopActive (const bool active)
 Set the emergency stop state.
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.
virtual void readSim (ros::Time time, ros::Duration period)
 Read state data from the simulated robot hardware.
virtual void writeSim (ros::Time time, ros::Duration period)
 Write commands to the simulated robot hardware.

Protected Types

enum  ControlMethod {
  EFFORT, POSITION, POSITION_PID, VELOCITY,
  VELOCITY_PID
}

Protected Member Functions

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)

Protected Attributes

bool e_stop_active_
hardware_interface::EffortJointInterface ej_interface_
joint_limits_interface::EffortJointSoftLimitsInterface ej_limits_interface_
joint_limits_interface::EffortJointSaturationInterface ej_sat_interface_
std::vector< ControlMethodjoint_control_methods_
std::vector< double > joint_effort_
std::vector< double > joint_effort_command_
std::vector< double > joint_effort_limits_
std::vector< double > joint_lower_limits_
std::vector< std::string > joint_names_
std::vector< double > joint_position_
std::vector< double > joint_position_command_
std::vector< int > joint_types_
std::vector< double > joint_upper_limits_
std::vector< double > joint_velocity_
std::vector< double > joint_velocity_command_
hardware_interface::JointStateInterface js_interface_
bool last_e_stop_active_
std::vector< double > last_joint_position_command_
unsigned int n_dof_
std::vector< control_toolbox::Pidpid_controllers_
hardware_interface::PositionJointInterface pj_interface_
joint_limits_interface::PositionJointSoftLimitsInterface pj_limits_interface_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
std::vector
< gazebo::physics::JointPtr > 
sim_joints_
hardware_interface::VelocityJointInterface vj_interface_
joint_limits_interface::VelocityJointSoftLimitsInterface vj_limits_interface_
joint_limits_interface::VelocityJointSaturationInterface vj_sat_interface_

Detailed Description

Definition at line 74 of file default_robot_hw_sim.h.


Member Enumeration Documentation

Enumerator:
EFFORT 
POSITION 
POSITION_PID 
VELOCITY 
VELOCITY_PID 

Definition at line 93 of file default_robot_hw_sim.h.


Member Function Documentation

void gazebo_ros_control::DefaultRobotHWSim::eStopActive ( const bool  active) [virtual]

Set the emergency stop state.

Set the simulated robot's emergency stop state. The default implementation of this function does nothing.

Parameters:
activetrue if the emergency stop is active, false if not.

Reimplemented from gazebo_ros_control::RobotHWSim.

Definition at line 356 of file default_robot_hw_sim.cpp.

bool gazebo_ros_control::DefaultRobotHWSim::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 
) [virtual]

Initialize the simulated robot hardware.

Initialize the simulated robot hardware.

Parameters:
robot_namespaceRobot namespace.
model_nhModel node handle.
parent_modelParent model.
urdf_modelURDF model.
transmissionsTransmissions.
Returns:
true if the simulated robot hardware is initialized successfully, false if not.

Implements gazebo_ros_control::RobotHWSim.

Definition at line 59 of file default_robot_hw_sim.cpp.

Read state data from the simulated robot hardware.

Read state data, such as joint positions and velocities, from the simulated robot hardware.

Parameters:
timeSimulation time.
periodTime since the last simulation step.

Implements gazebo_ros_control::RobotHWSim.

Definition at line 244 of file default_robot_hw_sim.cpp.

void gazebo_ros_control::DefaultRobotHWSim::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 
) [protected]

Definition at line 364 of file default_robot_hw_sim.cpp.

Write commands to the simulated robot hardware.

Write commands, such as joint position and velocity commands, to the simulated robot hardware.

Parameters:
timeSimulation time.
periodTime since the last simulation step.

Implements gazebo_ros_control::RobotHWSim.

Definition at line 263 of file default_robot_hw_sim.cpp.


Member Data Documentation

Definition at line 138 of file default_robot_hw_sim.h.

Definition at line 109 of file default_robot_hw_sim.h.

Definition at line 114 of file default_robot_hw_sim.h.

Definition at line 113 of file default_robot_hw_sim.h.

Definition at line 125 of file default_robot_hw_sim.h.

Definition at line 129 of file default_robot_hw_sim.h.

Definition at line 130 of file default_robot_hw_sim.h.

Definition at line 124 of file default_robot_hw_sim.h.

Definition at line 122 of file default_robot_hw_sim.h.

std::vector<std::string> gazebo_ros_control::DefaultRobotHWSim::joint_names_ [protected]

Definition at line 120 of file default_robot_hw_sim.h.

Definition at line 127 of file default_robot_hw_sim.h.

Definition at line 131 of file default_robot_hw_sim.h.

Definition at line 121 of file default_robot_hw_sim.h.

Definition at line 123 of file default_robot_hw_sim.h.

Definition at line 128 of file default_robot_hw_sim.h.

Definition at line 133 of file default_robot_hw_sim.h.

Definition at line 108 of file default_robot_hw_sim.h.

Definition at line 138 of file default_robot_hw_sim.h.

Definition at line 132 of file default_robot_hw_sim.h.

Definition at line 106 of file default_robot_hw_sim.h.

Definition at line 126 of file default_robot_hw_sim.h.

Definition at line 110 of file default_robot_hw_sim.h.

Definition at line 116 of file default_robot_hw_sim.h.

Definition at line 115 of file default_robot_hw_sim.h.

std::vector<gazebo::physics::JointPtr> gazebo_ros_control::DefaultRobotHWSim::sim_joints_ [protected]

Definition at line 135 of file default_robot_hw_sim.h.

Definition at line 111 of file default_robot_hw_sim.h.

Definition at line 118 of file default_robot_hw_sim.h.

Definition at line 117 of file default_robot_hw_sim.h.


The documentation for this class was generated from the following files:


gazebo_ros_control
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Thu Feb 23 2017 03:43:51