CombinedRobotHW. More...
#include <combined_robot_hw_sim.h>
Public Member Functions | |
CombinedRobotHWSim () | |
virtual void | doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
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 bool | prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
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... | |
virtual | ~CombinedRobotHWSim () |
![]() | |
virtual | ~RobotHWSim () |
![]() | |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | init (ros::NodeHandle &, ros::NodeHandle &) |
virtual void | read (const ros::Time &, const ros::Duration &) |
virtual void | read (const ros::Time &, const ros::Duration &) |
virtual SwitchState | switchResult () const |
virtual SwitchState | switchResult (const ControllerInfo &) const |
virtual void | write (const ros::Time &, const ros::Duration &) |
virtual void | write (const ros::Time &, const ros::Duration &) |
virtual | ~RobotHW ()=default |
![]() | |
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 | |
typedef pluginlib::ClassLoader< gazebo_ros_control::RobotHWSim > | class_loader_t |
![]() | |
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 | filterControllerList (const std::list< hardware_interface::ControllerInfo > &list, std::list< hardware_interface::ControllerInfo > &filtered_list, gazebo_ros_control::RobotHWSimSharedPtr robot_hw) |
Filters the start and stop lists so that they only contain the controllers and resources that correspond to the robot_hw interface manager. More... | |
Protected Attributes | |
class_loader_t | class_loader_ |
std::vector< gazebo_ros_control::RobotHWSimSharedPtr > | robot_hw_list_ |
![]() | |
std::vector< ResourceManagerBase * > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
Additional Inherited Members | |
![]() | |
enum | SwitchState { SwitchState::DONE, SwitchState::ONGOING, SwitchState::ERROR } |
CombinedRobotHW.
This class provides a way to combine RobotHW objects.
Definition at line 95 of file combined_robot_hw_sim.h.
|
protected |
Definition at line 98 of file combined_robot_hw_sim.h.
gazebo_ros_control::CombinedRobotHWSim::CombinedRobotHWSim | ( | ) |
Definition at line 76 of file combined_robot_hw_sim.cpp.
|
inlinevirtual |
Definition at line 112 of file combined_robot_hw_sim.h.
|
virtual |
Perform (in realtime) all necessary hardware interface switches in order to start and stop the given controllers. Start and stop list are disjoint. The feasability was checked in prepareSwitch() beforehand.
Reimplemented from hardware_interface::RobotHW.
Definition at line 172 of file combined_robot_hw_sim.cpp.
|
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 from gazebo_ros_control::RobotHWSim.
Definition at line 167 of file combined_robot_hw_sim.h.
|
protected |
Filters the start and stop lists so that they only contain the controllers and resources that correspond to the robot_hw interface manager.
Definition at line 207 of file combined_robot_hw_sim.cpp.
|
virtual |
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 80 of file combined_robot_hw_sim.cpp.
|
virtual |
Check (in non-realtime) if given controllers could be started and stopped from the current state of the RobotHW with regard to necessary hardware interface switches and prepare the switching. Start and stop list are disjoint. This handles the check and preparation, the actual switch is commited in doSwitch()
Reimplemented from hardware_interface::RobotHW.
Definition at line 154 of file combined_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 189 of file combined_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 198 of file combined_robot_hw_sim.cpp.
|
protected |
Definition at line 99 of file combined_robot_hw_sim.h.
|
protected |
Definition at line 100 of file combined_robot_hw_sim.h.