|
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) |
|
virtual void | handleDiag (LayerReport &report) |
|
| LayerGroupNoDiag (const std::string &n) |
|
| LayerGroup (const std::string &n) |
|
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 () |
|
virtual void | add (const VectorMemberSharedPtr &l) |
|
bool | callFunc (FuncType func, Data &status) |
|
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 () |
|
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) |
|
|
enum | LayerState |
|
typedef boost::shared_ptr< T > | VectorMemberSharedPtr |
|
| Error |
|
| Halt |
|
| Init |
|
const std::string | name |
|
| Off |
|
| Ready |
|
| Recover |
|
| Shutdown |
|
typedef std::vector< VectorMemberSharedPtr > | vector_type |
|
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 |
|
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) |
|
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 () |
|
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.