Public Member Functions | List of all members
gazebo_ros_control::RobotHWSim Class Referenceabstract

Gazebo plugin version of RobotHW. More...

#include <robot_hw_sim.h>

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

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 bool init (ros::NodeHandle &, ros::NodeHandle &)
 
virtual bool prepareSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual void read (const ros::Time &, const ros::Duration &)
 
virtual SwitchState switchResult (const ControllerInfo &) const
 
virtual SwitchState switchResult () const
 
virtual void write (const ros::Time &, const ros::Duration &)
 
virtual void write (const ros::Time &, const ros::Duration &)
 
virtual ~RobotHW ()=default
 
- 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

- Public Types inherited from hardware_interface::RobotHW
enum  SwitchState
 
- Public Attributes inherited from hardware_interface::RobotHW
 DONE
 
 ERROR
 
 ONGOING
 
- 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
std::vector< ResourceManagerBase *> interface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ~RobotHWSim()

virtual gazebo_ros_control::RobotHWSim::~RobotHWSim ( )
inlinevirtual

Definition at line 72 of file robot_hw_sim.h.

Member Function Documentation

◆ eStopActive()

virtual void gazebo_ros_control::RobotHWSim::eStopActive ( const bool  active)
inlinevirtual

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 in gazebo_ros_control::DefaultRobotHWSim.

Definition at line 113 of file robot_hw_sim.h.

◆ initSim()

virtual bool gazebo_ros_control::RobotHWSim::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 
)
pure 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.

Implemented in gazebo_ros_control::DefaultRobotHWSim.

◆ readSim()

virtual void gazebo_ros_control::RobotHWSim::readSim ( ros::Time  time,
ros::Duration  period 
)
pure virtual

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.

Implemented in gazebo_ros_control::DefaultRobotHWSim.

◆ writeSim()

virtual void gazebo_ros_control::RobotHWSim::writeSim ( ros::Time  time,
ros::Duration  period 
)
pure virtual

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.

Implemented in gazebo_ros_control::DefaultRobotHWSim.


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


gazebo_ros_control
Author(s): Jonathan Bohren, Dave Coleman
autogenerated on Wed Aug 24 2022 02:48:00