#include <robot_layer.h>

| Classes | |
| struct | SwitchData | 
| Public Member Functions | |
| void | add (const std::string &name, HandleLayerBaseSharedPtr handle) | 
| virtual void | doSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) | 
| void | enforce (const ros::Duration &period, bool reset) | 
| urdf::JointConstSharedPtr | getJoint (const std::string &n) const | 
| virtual void | handleInit (canopen::LayerStatus &status) | 
| virtual bool | prepareSwitch (const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) | 
| RobotLayer (ros::NodeHandle nh) | |
|  Public Member Functions inherited from canopen::LayerGroupNoDiag< HandleLayerBase > | |
| virtual void | handleDiag (LayerReport &report) | 
| LayerGroupNoDiag (const std::string &n) | |
|  Public Member Functions inherited from canopen::LayerGroup< T > | |
| LayerGroup (const std::string &n) | |
|  Public Member Functions inherited from canopen::Layer | |
| void | diag (LayerReport &report) | 
| LayerState | getLayerState () | 
| void | halt (LayerStatus &status) | 
| void | init (LayerStatus &status) | 
| Layer (const std::string &n) | |
| void | read (LayerStatus &status) | 
| void | recover (LayerStatus &status) | 
| void | shutdown (LayerStatus &status) | 
| void | write (LayerStatus &status) | 
| virtual | ~Layer () | 
|  Public Member Functions inherited from canopen::VectorHelper< T > | |
| virtual void | add (const VectorMemberSharedPtr &l) | 
| bool | callFunc (FuncType func, Data &status) | 
|  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 bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) | 
| virtual void | read (const ros::Time &time, const ros::Duration &period) | 
| virtual void | read (const ros::Time &time, const ros::Duration &period) | 
| RobotHW () | |
| virtual void | write (const ros::Time &time, const ros::Duration &period) | 
| virtual void | write (const ros::Time &time, const ros::Duration &period) | 
| 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) | 
| Private Types | |
| typedef boost::unordered_map< std::string, HandleLayerBaseSharedPtr > | HandleMap | 
| typedef std::vector< SwitchData > | SwitchContainer | 
| typedef boost::unordered_map< std::string, SwitchContainer > | SwitchMap | 
| Private Member Functions | |
| void | stopControllers (const std::vector< std::string > controllers) | 
| Additional Inherited Members | |
|  Public Types inherited from canopen::Layer | |
| enum | LayerState | 
|  Public Types inherited from canopen::VectorHelper< T > | |
| typedef boost::shared_ptr< T > | VectorMemberSharedPtr | 
|  Public Attributes inherited from canopen::Layer | |
| Error | |
| Halt | |
| Init | |
| const std::string | name | 
| Off | |
| Ready | |
| Recover | |
| Shutdown | |
|  Protected Types inherited from canopen::VectorHelper< T > | |
| typedef std::vector< VectorMemberSharedPtr > | vector_type | 
|  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 Member Functions inherited from canopen::LayerGroup< T > | |
| void | call_or_fail (FuncType func, FailType fail, Data &status) | 
| void | call_or_fail_rev (FuncType func, FailType fail, Data &status) | 
| virtual void | handleHalt (LayerStatus &status) | 
| virtual void | handleRead (LayerStatus &status, const LayerState ¤t_state) | 
| virtual void | handleRecover (LayerStatus &status) | 
| virtual void | handleShutdown (LayerStatus &status) | 
| virtual void | handleWrite (LayerStatus &status, const LayerState ¤t_state) | 
|  Protected Member Functions inherited from canopen::VectorHelper< T > | |
| vector_type::iterator | call (FuncType func, Data &status) | 
| vector_type::iterator | call (FuncType func, Data &status) | 
| vector_type::reverse_iterator | call_rev (FuncType func, Data &status) | 
| vector_type::reverse_iterator | call_rev (FuncType func, Data &status) | 
| void | destroy () | 
|  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_ | 
Definition at line 18 of file robot_layer.h.
| 
 | private | 
Definition at line 34 of file robot_layer.h.
| 
 | private | 
Definition at line 41 of file robot_layer.h.
| 
 | private | 
Definition at line 42 of file robot_layer.h.
| RobotLayer::RobotLayer | ( | ros::NodeHandle | nh | ) | 
Definition at line 31 of file robot_layer.cpp.
| void RobotLayer::add | ( | const std::string & | name, | 
| HandleLayerBaseSharedPtr | handle | ||
| ) | 
Definition at line 26 of file robot_layer.cpp.
| 
 | virtual | 
Reimplemented from hardware_interface::RobotHW.
Definition at line 222 of file robot_layer.cpp.
| void RobotLayer::enforce | ( | const ros::Duration & | period, | 
| bool | reset | ||
| ) | 
Definition at line 77 of file robot_layer.cpp.
| 
 | inline | 
Definition at line 51 of file robot_layer.h.
| 
 | virtual | 
Reimplemented from canopen::LayerGroup< T >.
Definition at line 41 of file robot_layer.cpp.
| 
 | virtual | 
Reimplemented from hardware_interface::RobotHW.
Definition at line 106 of file robot_layer.cpp.
| 
 | private | 
Definition at line 18 of file robot_layer.cpp.
| 
 | private | 
Definition at line 22 of file robot_layer.h.
| 
 | private | 
Definition at line 29 of file robot_layer.h.
| 
 | private | 
Definition at line 28 of file robot_layer.h.
| 
 | private | 
Definition at line 45 of file robot_layer.h.
| 
 | private | 
Definition at line 35 of file robot_layer.h.
| 
 | private | 
Definition at line 31 of file robot_layer.h.
| 
 | private | 
Definition at line 20 of file robot_layer.h.
| 
 | private | 
Definition at line 25 of file robot_layer.h.
| 
 | private | 
Definition at line 24 of file robot_layer.h.
| 
 | private | 
Definition at line 19 of file robot_layer.h.
| 
 | private | 
Definition at line 43 of file robot_layer.h.
| 
 | private | 
Definition at line 32 of file robot_layer.h.
| 
 | private | 
Definition at line 21 of file robot_layer.h.
| 
 | private | 
Definition at line 27 of file robot_layer.h.
| 
 | private | 
Definition at line 26 of file robot_layer.h.