2 #ifndef CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_ 3 #define CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_ 6 #include <boost/shared_ptr.hpp>
boost::shared_ptr< ControllerManagerLayer > cm_
virtual bool setup_chain()
boost::shared_ptr< canopen::LayerGroupNoDiag< canopen::MotorBase > > motors_
MotorChain(const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv)
ClassAllocator< canopen::MotorBase > motor_allocator_
virtual bool nodeAdded(XmlRpc::XmlRpcValue ¶ms, const canopen::NodeSharedPtr &node, const LoggerSharedPtr &logger)
RobotLayerSharedPtr robot_layer_