#include <default_robot_hw_sim.h>
Public Member Functions | |
virtual void | eStopActive (const bool active) |
Set the emergency stop state. More... | |
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. More... | |
virtual void | readSim (ros::Time time, ros::Duration period) |
Read state data from the simulated robot hardware. More... | |
virtual void | writeSim (ros::Time time, ros::Duration period) |
Write commands to the simulated robot hardware. More... | |
Public Member Functions inherited from gazebo_ros_control::RobotHWSim | |
virtual | ~RobotHWSim () |
Public Member Functions inherited from hardware_interface::RobotHW | |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
RobotHW () | |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual | ~RobotHW () |
Public Member Functions inherited from hardware_interface::InterfaceManager | |
T * | get () |
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
std::vector< std::string > | getNames () const |
void | registerInterface (T *iface) |
void | registerInterfaceManager (InterfaceManager *iface_man) |
Protected Types | |
enum | ControlMethod { EFFORT, POSITION, POSITION_PID, VELOCITY, VELOCITY_PID } |
Protected Types inherited from hardware_interface::InterfaceManager | |
typedef std::vector< InterfaceManager * > | InterfaceManagerVector |
typedef std::map< std::string, void * > | InterfaceMap |
typedef std::map< std::string, std::vector< std::string > > | ResourceMap |
typedef std::map< std::string, size_t > | SizeMap |
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) |
Definition at line 74 of file default_robot_hw_sim.h.
|
protected |
Enumerator | |
---|---|
EFFORT | |
POSITION | |
POSITION_PID | |
VELOCITY | |
VELOCITY_PID |
Definition at line 93 of file default_robot_hw_sim.h.
|
virtual |
Set the emergency stop state.
Set the simulated robot's emergency stop state. The default implementation of this function does nothing.
active | true if the emergency stop is active, false if not. |
Reimplemented from gazebo_ros_control::RobotHWSim.
Definition at line 385 of file default_robot_hw_sim.cpp.
|
virtual |
Initialize the simulated robot hardware.
Initialize the simulated robot hardware.
robot_namespace | Robot namespace. |
model_nh | Model node handle. |
parent_model | Parent model. |
urdf_model | URDF model. |
transmissions | Transmissions. |
true
if the simulated robot hardware is initialized successfully, false
if not. Implements gazebo_ros_control::RobotHWSim.
Definition at line 60 of file default_robot_hw_sim.cpp.
|
virtual |
Read state data from the simulated robot hardware.
Read state data, such as joint positions and velocities, from the simulated robot hardware.
time | Simulation time. |
period | Time since the last simulation step. |
Implements gazebo_ros_control::RobotHWSim.
Definition at line 261 of file default_robot_hw_sim.cpp.
|
protected |
Definition at line 393 of file default_robot_hw_sim.cpp.
|
virtual |
Write commands to the simulated robot hardware.
Write commands, such as joint position and velocity commands, to the simulated robot hardware.
time | Simulation time. |
period | Time since the last simulation step. |
Implements gazebo_ros_control::RobotHWSim.
Definition at line 285 of file default_robot_hw_sim.cpp.
|
protected |
Definition at line 140 of file default_robot_hw_sim.h.
|
protected |
Definition at line 109 of file default_robot_hw_sim.h.
|
protected |
Definition at line 114 of file default_robot_hw_sim.h.
|
protected |
Definition at line 113 of file default_robot_hw_sim.h.
|
protected |
Definition at line 125 of file default_robot_hw_sim.h.
|
protected |
Definition at line 129 of file default_robot_hw_sim.h.
|
protected |
Definition at line 130 of file default_robot_hw_sim.h.
|
protected |
Definition at line 124 of file default_robot_hw_sim.h.
|
protected |
Definition at line 122 of file default_robot_hw_sim.h.
|
protected |
Definition at line 120 of file default_robot_hw_sim.h.
|
protected |
Definition at line 127 of file default_robot_hw_sim.h.
|
protected |
Definition at line 131 of file default_robot_hw_sim.h.
|
protected |
Definition at line 121 of file default_robot_hw_sim.h.
|
protected |
Definition at line 123 of file default_robot_hw_sim.h.
|
protected |
Definition at line 128 of file default_robot_hw_sim.h.
|
protected |
Definition at line 133 of file default_robot_hw_sim.h.
|
protected |
Definition at line 108 of file default_robot_hw_sim.h.
|
protected |
Definition at line 140 of file default_robot_hw_sim.h.
|
protected |
Definition at line 132 of file default_robot_hw_sim.h.
|
protected |
Definition at line 106 of file default_robot_hw_sim.h.
|
protected |
Definition at line 137 of file default_robot_hw_sim.h.
|
protected |
Definition at line 126 of file default_robot_hw_sim.h.
|
protected |
Definition at line 110 of file default_robot_hw_sim.h.
|
protected |
Definition at line 116 of file default_robot_hw_sim.h.
|
protected |
Definition at line 115 of file default_robot_hw_sim.h.
|
protected |
Definition at line 135 of file default_robot_hw_sim.h.
|
protected |
Definition at line 111 of file default_robot_hw_sim.h.
|
protected |
Definition at line 118 of file default_robot_hw_sim.h.
|
protected |
Definition at line 117 of file default_robot_hw_sim.h.