controller_manager_layer.h
Go to the documentation of this file.
00001 
00002 #ifndef CANOPEN_MOTOR_NODE_CONTROLLER_MANAGER_LAYER_H_
00003 #define CANOPEN_MOTOR_NODE_CONTROLLER_MANAGER_LAYER_H_
00004 
00005 #include <ros/node_handle.h>
00006 #include <boost/shared_ptr.hpp>
00007 #include <boost/atomic.hpp>
00008 #include <canopen_master/canopen.h>
00009 #include <canopen_motor_node/robot_layer.h>
00010 
00011 // forward declarations
00012 namespace controller_manager {
00013     class ControllerManager;
00014 }
00015 
00016 namespace canopen {
00017 
00018 class ControllerManagerLayer : public canopen::Layer {
00019     boost::shared_ptr<controller_manager::ControllerManager> cm_;
00020     boost::shared_ptr<canopen::RobotLayer> robot_;
00021     ros::NodeHandle nh_;
00022 
00023     canopen::time_point last_time_;
00024     boost::atomic<bool> recover_;
00025     const ros::Duration fixed_period_;
00026 
00027 public:
00028     ControllerManagerLayer(const boost::shared_ptr<canopen::RobotLayer> robot, const ros::NodeHandle &nh, const ros::Duration &fixed_period)
00029     :Layer("ControllerManager"), robot_(robot), nh_(nh), fixed_period_(fixed_period) {
00030     }
00031 
00032     virtual void handleRead(canopen::LayerStatus &status, const LayerState &current_state);
00033     virtual void handleWrite(canopen::LayerStatus &status, const LayerState &current_state);
00034     virtual void handleDiag(canopen::LayerReport &report) { /* nothing to do */ }
00035     virtual void handleHalt(canopen::LayerStatus &status) { /* nothing to do (?) */ }
00036     virtual void handleInit(canopen::LayerStatus &status);
00037     virtual void handleRecover(canopen::LayerStatus &status);
00038     virtual void handleShutdown(canopen::LayerStatus &status);
00039 };
00040 
00041 }  //  namespace canopen
00042 
00043 #endif /* CANOPEN_MOTOR_NODE_CONTROLLER_MANAGER_LAYER_H_ */


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:55