#include <combined_robot_hw.h>
Public Member Functions | |
CombinedRobotHW () | |
virtual void | doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
The init function is called to initialize the RobotHW from a non-realtime thread. More... | |
virtual bool | prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual | ~CombinedRobotHW () |
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 |
RobotHW () | |
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 Member Functions | |
void | filterControllerList (const std::list< hardware_interface::ControllerInfo > &list, std::list< hardware_interface::ControllerInfo > &filtered_list, hardware_interface::RobotHWSharedPtr 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... | |
virtual bool | loadRobotHW (const std::string &name) |
Protected Attributes | |
std::vector< hardware_interface::RobotHWSharedPtr > | robot_hw_list_ |
pluginlib::ClassLoader< hardware_interface::RobotHW > | robot_hw_loader_ |
ros::NodeHandle | robot_hw_nh_ |
ros::NodeHandle | root_nh_ |
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_ |
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 |
This class provides a way to combine RobotHW objects.
Definition at line 52 of file combined_robot_hw.h.
combined_robot_hw::CombinedRobotHW::CombinedRobotHW | ( | ) |
Definition at line 33 of file combined_robot_hw.cpp.
|
inlinevirtual |
Definition at line 57 of file combined_robot_hw.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 81 of file combined_robot_hw.cpp.
|
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 208 of file combined_robot_hw.cpp.
|
virtual |
The init function is called to initialize the RobotHW from a non-realtime thread.
root_nh | A NodeHandle in the root of the caller namespace. |
robot_hw_nh | A NodeHandle in the namespace from which the RobotHW should read its configuration. |
Reimplemented from hardware_interface::RobotHW.
Definition at line 37 of file combined_robot_hw.cpp.
|
protectedvirtual |
Definition at line 99 of file combined_robot_hw.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 61 of file combined_robot_hw.cpp.
|
virtual |
Reads data from the robot HW
time | The current time |
period | The time passed since the last call to read |
Reimplemented from hardware_interface::RobotHW.
Definition at line 187 of file combined_robot_hw.cpp.
|
virtual |
Writes data to the robot HW
time | The current time |
period | The time passed since the last call to write |
Reimplemented from hardware_interface::RobotHW.
Definition at line 198 of file combined_robot_hw.cpp.
|
protected |
Definition at line 107 of file combined_robot_hw.h.
|
protected |
Definition at line 106 of file combined_robot_hw.h.
|
protected |
Definition at line 105 of file combined_robot_hw.h.
|
protected |
Definition at line 104 of file combined_robot_hw.h.