Public Member Functions | List of all members
hardware_interface::RobotHW Class Reference

Robot Hardware Interface and Resource Manager. More...

#include <robot_hw.h>

Inheritance diagram for hardware_interface::RobotHW:
Inheritance graph
[legend]

Public Member Functions

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...
 
 RobotHW ()
 
virtual ~RobotHW ()
 
Resource Management
virtual bool checkForConflict (const std::list< ControllerInfo > &info) const
 
Hardware Interface Switching
virtual bool prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
 
virtual void doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
 
virtual void read (const ros::Time &time, const ros::Duration &period)
 
virtual void write (const ros::Time &time, const ros::Duration &period)
 
- Public Member Functions inherited from hardware_interface::InterfaceManager
template<class T >
T * get ()
 Get an interface. More...
 
std::vector< std::string > getInterfaceResources (std::string iface_type) const
 Get the resource names registered to an interface, specified by type (as this class only stores one interface per type) More...
 
std::vector< std::string > getNames () const
 
template<class T >
void registerInterface (T *iface)
 Register an interface. More...
 
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< ResourceManagerBaseinterface_destruction_list_
 
InterfaceManagerVector interface_managers_
 
InterfaceMap interfaces_
 
InterfaceMap interfaces_combo_
 
SizeMap num_ifaces_registered_
 
ResourceMap resources_
 This will allow us to check the resources based on the demangled type name of the interface. More...
 

Detailed Description

Robot Hardware Interface and Resource Manager.

This class provides a standardized interface to a set of robot hardware interfaces to the controller manager. It performs resource conflict checking for a given set of controllers and maintains a map of hardware interfaces. It is meant to be used as a base class for abstracting custom robot hardware.

The hardware interface map (interfaces_) is a 1-to-1 map between the names of interface types derived from HardwareInterface and instances of those interface types.

Definition at line 57 of file robot_hw.h.

Constructor & Destructor Documentation

hardware_interface::RobotHW::RobotHW ( )
inline

Definition at line 60 of file robot_hw.h.

virtual hardware_interface::RobotHW::~RobotHW ( )
inlinevirtual

Definition at line 65 of file robot_hw.h.

Member Function Documentation

virtual bool hardware_interface::RobotHW::checkForConflict ( const std::list< ControllerInfo > &  info) const
inlinevirtual

Check (in non-realtime) if the given set of controllers is allowed to run simultaneously.

This default implementation simply checks if any two controllers use the same resource.

Definition at line 91 of file robot_hw.h.

virtual void hardware_interface::RobotHW::doSwitch ( const std::list< ControllerInfo > &  ,
const std::list< ControllerInfo > &   
)
inlinevirtual

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.

Definition at line 147 of file robot_hw.h.

virtual bool hardware_interface::RobotHW::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
inlinevirtual

The init function is called to initialize the RobotHW from a non-realtime thread.

Parameters
root_nhA NodeHandle in the root of the caller namespace.
robot_hw_nhA NodeHandle in the namespace from which the RobotHW should read its configuration.
Returns
True if initialization was successful

Definition at line 80 of file robot_hw.h.

virtual bool hardware_interface::RobotHW::prepareSwitch ( const std::list< ControllerInfo > &  start_list,
const std::list< ControllerInfo > &  stop_list 
)
inlinevirtual

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()

Definition at line 140 of file robot_hw.h.

virtual void hardware_interface::RobotHW::read ( const ros::Time time,
const ros::Duration period 
)
inlinevirtual

Reads data from the robot HW

Parameters
timeThe current time
periodThe time passed since the last call to read

Definition at line 156 of file robot_hw.h.

virtual void hardware_interface::RobotHW::write ( const ros::Time time,
const ros::Duration period 
)
inlinevirtual

Writes data to the robot HW

Parameters
timeThe current time
periodThe time passed since the last call to write

Definition at line 164 of file robot_hw.h.


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


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Mon Apr 20 2020 03:52:05