Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
combined_robot_hw::CombinedRobotHW Class Reference

CombinedRobotHW. More...

#include <combined_robot_hw.h>

Inheritance diagram for combined_robot_hw::CombinedRobotHW:
Inheritance graph
[legend]

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::RobotHWSharedPtrrobot_hw_list_
 
pluginlib::ClassLoader< hardware_interface::RobotHWrobot_hw_loader_
 
ros::NodeHandle robot_hw_nh_
 
ros::NodeHandle root_nh_
 
- 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_
 

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
 

Detailed Description

CombinedRobotHW.

This class provides a way to combine RobotHW objects.

Definition at line 52 of file combined_robot_hw.h.

Constructor & Destructor Documentation

combined_robot_hw::CombinedRobotHW::CombinedRobotHW ( )

Definition at line 33 of file combined_robot_hw.cpp.

virtual combined_robot_hw::CombinedRobotHW::~CombinedRobotHW ( )
inlinevirtual

Definition at line 57 of file combined_robot_hw.h.

Member Function Documentation

void combined_robot_hw::CombinedRobotHW::doSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
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.

void combined_robot_hw::CombinedRobotHW::filterControllerList ( const std::list< hardware_interface::ControllerInfo > &  list,
std::list< hardware_interface::ControllerInfo > &  filtered_list,
hardware_interface::RobotHWSharedPtr  robot_hw 
)
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.

bool combined_robot_hw::CombinedRobotHW::init ( ros::NodeHandle root_nh,
ros::NodeHandle robot_hw_nh 
)
virtual

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

Reimplemented from hardware_interface::RobotHW.

Definition at line 37 of file combined_robot_hw.cpp.

bool combined_robot_hw::CombinedRobotHW::loadRobotHW ( const std::string &  name)
protectedvirtual

Definition at line 99 of file combined_robot_hw.cpp.

bool combined_robot_hw::CombinedRobotHW::prepareSwitch ( const std::list< hardware_interface::ControllerInfo > &  start_list,
const std::list< hardware_interface::ControllerInfo > &  stop_list 
)
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.

void combined_robot_hw::CombinedRobotHW::read ( const ros::Time time,
const ros::Duration period 
)
virtual

Reads data from the robot HW

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

Reimplemented from hardware_interface::RobotHW.

Definition at line 187 of file combined_robot_hw.cpp.

void combined_robot_hw::CombinedRobotHW::write ( const ros::Time time,
const ros::Duration period 
)
virtual

Writes data to the robot HW

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

Reimplemented from hardware_interface::RobotHW.

Definition at line 198 of file combined_robot_hw.cpp.

Member Data Documentation

std::vector<hardware_interface::RobotHWSharedPtr> combined_robot_hw::CombinedRobotHW::robot_hw_list_
protected

Definition at line 107 of file combined_robot_hw.h.

pluginlib::ClassLoader<hardware_interface::RobotHW> combined_robot_hw::CombinedRobotHW::robot_hw_loader_
protected

Definition at line 106 of file combined_robot_hw.h.

ros::NodeHandle combined_robot_hw::CombinedRobotHW::robot_hw_nh_
protected

Definition at line 105 of file combined_robot_hw.h.

ros::NodeHandle combined_robot_hw::CombinedRobotHW::root_nh_
protected

Definition at line 104 of file combined_robot_hw.h.


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


combined_robot_hw
Author(s): Toni Oliver
autogenerated on Fri Jun 7 2019 22:00:05