#include <controller_manager_layer.h>

Public Member Functions | |
| ControllerManagerLayer (const boost::shared_ptr< canopen::RobotLayer > robot, const ros::NodeHandle &nh, const ros::Duration &fixed_period) | |
| virtual void | handleDiag (canopen::LayerReport &report) |
| virtual void | handleHalt (canopen::LayerStatus &status) |
| virtual void | handleInit (canopen::LayerStatus &status) |
| virtual void | handleRead (canopen::LayerStatus &status, const LayerState ¤t_state) |
| virtual void | handleRecover (canopen::LayerStatus &status) |
| virtual void | handleShutdown (canopen::LayerStatus &status) |
| virtual void | handleWrite (canopen::LayerStatus &status, const LayerState ¤t_state) |
Private Attributes | |
| boost::shared_ptr < controller_manager::ControllerManager > | cm_ |
| const ros::Duration | fixed_period_ |
| canopen::time_point | last_time_ |
| ros::NodeHandle | nh_ |
| boost::atomic< bool > | recover_ |
| boost::shared_ptr < canopen::RobotLayer > | robot_ |
Definition at line 18 of file controller_manager_layer.h.
| canopen::ControllerManagerLayer::ControllerManagerLayer | ( | const boost::shared_ptr< canopen::RobotLayer > | robot, |
| const ros::NodeHandle & | nh, | ||
| const ros::Duration & | fixed_period | ||
| ) | [inline] |
Definition at line 28 of file controller_manager_layer.h.
| virtual void canopen::ControllerManagerLayer::handleDiag | ( | canopen::LayerReport & | report | ) | [inline, virtual] |
Implements canopen::Layer.
Definition at line 34 of file controller_manager_layer.h.
| virtual void canopen::ControllerManagerLayer::handleHalt | ( | canopen::LayerStatus & | status | ) | [inline, virtual] |
Implements canopen::Layer.
Definition at line 35 of file controller_manager_layer.h.
| void ControllerManagerLayer::handleInit | ( | canopen::LayerStatus & | status | ) | [virtual] |
Implements canopen::Layer.
Definition at line 36 of file controller_manager_layer.cpp.
| void ControllerManagerLayer::handleRead | ( | canopen::LayerStatus & | status, |
| const LayerState & | current_state | ||
| ) | [virtual] |
Implements canopen::Layer.
Definition at line 7 of file controller_manager_layer.cpp.
| void ControllerManagerLayer::handleRecover | ( | canopen::LayerStatus & | status | ) | [virtual] |
Implements canopen::Layer.
Definition at line 46 of file controller_manager_layer.cpp.
| void ControllerManagerLayer::handleShutdown | ( | canopen::LayerStatus & | status | ) | [virtual] |
Implements canopen::Layer.
Definition at line 51 of file controller_manager_layer.cpp.
| void ControllerManagerLayer::handleWrite | ( | canopen::LayerStatus & | status, |
| const LayerState & | current_state | ||
| ) | [virtual] |
Implements canopen::Layer.
Definition at line 13 of file controller_manager_layer.cpp.
boost::shared_ptr<controller_manager::ControllerManager> canopen::ControllerManagerLayer::cm_ [private] |
Definition at line 19 of file controller_manager_layer.h.
const ros::Duration canopen::ControllerManagerLayer::fixed_period_ [private] |
Definition at line 25 of file controller_manager_layer.h.
Definition at line 23 of file controller_manager_layer.h.
Definition at line 21 of file controller_manager_layer.h.
boost::atomic<bool> canopen::ControllerManagerLayer::recover_ [private] |
Definition at line 24 of file controller_manager_layer.h.
boost::shared_ptr<canopen::RobotLayer> canopen::ControllerManagerLayer::robot_ [private] |
Definition at line 20 of file controller_manager_layer.h.