#include <motor_chain.h>

Public Member Functions | |
| MotorChain (const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv) | |
| virtual bool | setup_chain () |
Private Member Functions | |
| virtual bool | nodeAdded (XmlRpc::XmlRpcValue ¶ms, const boost::shared_ptr< Node > &node, const boost::shared_ptr< Logger > &logger) |
Private Attributes | |
| boost::shared_ptr < ControllerManagerLayer > | cm_ |
| ClassAllocator < canopen::MotorBase > | motor_allocator_ |
| boost::shared_ptr < canopen::LayerGroupNoDiag < canopen::MotorBase > > | motors_ |
| boost::shared_ptr< RobotLayer > | robot_layer_ |
Definition at line 15 of file motor_chain.h.
| MotorChain::MotorChain | ( | const ros::NodeHandle & | nh, |
| const ros::NodeHandle & | nh_priv | ||
| ) |
Definition at line 28 of file motor_chain.cpp.
| bool MotorChain::nodeAdded | ( | XmlRpc::XmlRpcValue & | params, |
| const boost::shared_ptr< Node > & | node, | ||
| const boost::shared_ptr< Logger > & | logger | ||
| ) | [private, virtual] |
Definition at line 31 of file motor_chain.cpp.
| bool MotorChain::setup_chain | ( | ) | [virtual] |
Reimplemented from canopen::RosChain.
Definition at line 82 of file motor_chain.cpp.
boost::shared_ptr<ControllerManagerLayer> canopen::MotorChain::cm_ [private] |
Definition at line 20 of file motor_chain.h.
Definition at line 16 of file motor_chain.h.
boost::shared_ptr< canopen::LayerGroupNoDiag<canopen::MotorBase> > canopen::MotorChain::motors_ [private] |
Definition at line 17 of file motor_chain.h.
boost::shared_ptr<RobotLayer> canopen::MotorChain::robot_layer_ [private] |
Definition at line 18 of file motor_chain.h.