motor_chain.h
Go to the documentation of this file.
00001 
00002 #ifndef CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_
00003 #define CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_
00004 
00005 #include <ros/node_handle.h>
00006 #include <boost/shared_ptr.hpp>
00007 #include <canopen_chain_node/ros_chain.h>
00008 
00009 #include <canopen_motor_node/robot_layer.h>
00010 #include <canopen_motor_node/controller_manager_layer.h>
00011 
00012 
00013 namespace canopen {
00014 
00015 class MotorChain : public canopen::RosChain {
00016     ClassAllocator<canopen::MotorBase> motor_allocator_;
00017     boost::shared_ptr< canopen::LayerGroupNoDiag<canopen::MotorBase> > motors_;
00018     boost::shared_ptr<RobotLayer> robot_layer_;
00019 
00020     boost::shared_ptr<ControllerManagerLayer> cm_;
00021 
00022     virtual bool nodeAdded(XmlRpc::XmlRpcValue &params, const boost::shared_ptr<Node> &node, const boost::shared_ptr<Logger> &logger);
00023 
00024 public:
00025     MotorChain(const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv);
00026 
00027     virtual bool setup_chain();
00028 };
00029 
00030 }  // namespace canopen
00031 
00032 #endif /* INCLUDE_CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_ */


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