motor_chain.h
Go to the documentation of this file.
1 
2 #ifndef CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_
3 #define CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_
4 
5 #include <ros/node_handle.h>
6 #include <boost/shared_ptr.hpp>
8 
11 
12 
13 namespace canopen {
14 
15 class MotorChain : public canopen::RosChain {
19 
21 
22  virtual bool nodeAdded(XmlRpc::XmlRpcValue &params, const canopen::NodeSharedPtr &node, const LoggerSharedPtr &logger);
23 
24 public:
25  MotorChain(const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv);
26 
27  virtual bool setup_chain();
28 };
29 
30 } // namespace canopen
31 
32 #endif /* INCLUDE_CANOPEN_MOTOR_NODE_MOTOR_CHAIN_H_ */
boost::shared_ptr< ControllerManagerLayer > cm_
Definition: motor_chain.h:20
virtual bool setup_chain()
Definition: motor_chain.cpp:82
boost::shared_ptr< canopen::LayerGroupNoDiag< canopen::MotorBase > > motors_
Definition: motor_chain.h:17
MotorChain(const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv)
Definition: motor_chain.cpp:28
ClassAllocator< canopen::MotorBase > motor_allocator_
Definition: motor_chain.h:16
virtual bool nodeAdded(XmlRpc::XmlRpcValue &params, const canopen::NodeSharedPtr &node, const LoggerSharedPtr &logger)
Definition: motor_chain.cpp:31
RobotLayerSharedPtr robot_layer_
Definition: motor_chain.h:18


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:47