Gazebo plugin version of RobotHW. More...
#include <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)=0 |
Initialize the simulated robot hardware. More... | |
virtual void | readSim (ros::Time time, ros::Duration period)=0 |
Read state data from the simulated robot hardware. More... | |
virtual void | writeSim (ros::Time time, ros::Duration period)=0 |
Write commands to the simulated robot hardware. More... | |
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) |
Additional Inherited Members | |
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 Attributes inherited from hardware_interface::InterfaceManager | |
boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
Gazebo plugin version of RobotHW.
An object of class RobotHWSim represents a robot's simulated hardware.
Definition at line 68 of file robot_hw_sim.h.
|
inlinevirtual |
Definition at line 72 of file robot_hw_sim.h.
|
inlinevirtual |
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 in gazebo_ros_control::DefaultRobotHWSim.
Definition at line 113 of file robot_hw_sim.h.
|
pure 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. Implemented in gazebo_ros_control::DefaultRobotHWSim.
|
pure 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. |
Implemented in gazebo_ros_control::DefaultRobotHWSim.
|
pure 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. |
Implemented in gazebo_ros_control::DefaultRobotHWSim.