Public Member Functions | Private Member Functions | Private Attributes | List of all members
canopen::MotorChain Class Reference

#include <motor_chain.h>

Inheritance diagram for canopen::MotorChain:
Inheritance graph
[legend]

Public Member Functions

 MotorChain (const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv)
 
virtual bool setup_chain ()
 
- Public Member Functions inherited from canopen::RosChain
 RosChain (const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv)
 
bool setup ()
 
virtual ~RosChain ()
 
- Public Member Functions inherited from canopen::LayerStack
 LayerStack (const std::string &n)
 
- Public Member Functions inherited from LayerGroup<>
 LayerGroup (const std::string &n)
 
- Public Member Functions inherited from canopen::Layer
void diag (LayerReport &report)
 
LayerState getLayerState ()
 
void halt (LayerStatus &status)
 
void init (LayerStatus &status)
 
 Layer (const std::string &n)
 
void read (LayerStatus &status)
 
void recover (LayerStatus &status)
 
void shutdown (LayerStatus &status)
 
void write (LayerStatus &status)
 
virtual ~Layer ()
 
- Public Member Functions inherited from VectorHelper< Layer >
virtual void add (const VectorMemberSharedPtr &l)
 
bool callFunc (FuncType func, Data &status)
 

Private Member Functions

virtual bool nodeAdded (XmlRpc::XmlRpcValue &params, const canopen::NodeSharedPtr &node, const LoggerSharedPtr &logger)
 

Private Attributes

boost::shared_ptr< ControllerManagerLayercm_
 
ClassAllocator< canopen::MotorBasemotor_allocator_
 
boost::shared_ptr< canopen::LayerGroupNoDiag< canopen::MotorBase > > motors_
 
RobotLayerSharedPtr robot_layer_
 

Additional Inherited Members

- Public Types inherited from canopen::Layer
enum  LayerState
 
- Public Types inherited from VectorHelper< Layer >
typedef boost::shared_ptr< Layer > VectorMemberSharedPtr
 
- Public Attributes inherited from canopen::Layer
 Error
 
 Halt
 
 Init
 
const std::string name
 
 Off
 
 Ready
 
 Recover
 
 Shutdown
 
- Protected Types inherited from VectorHelper< Layer >
typedef std::vector< VectorMemberSharedPtrvector_type
 
- Protected Member Functions inherited from canopen::RosChain
bool handle_get_object (canopen_chain_node::GetObject::Request &req, canopen_chain_node::GetObject::Response &res)
 
virtual bool handle_halt (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
virtual bool handle_init (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
virtual bool handle_recover (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
bool handle_set_object (canopen_chain_node::SetObject::Request &req, canopen_chain_node::SetObject::Response &res)
 
virtual bool handle_shutdown (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
virtual void handleShutdown (LayerStatus &status)
 
virtual void handleWrite (LayerStatus &status, const LayerState &current_state)
 
void logState (const can::State &s)
 
void report_diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void run ()
 
bool setup_bus ()
 
bool setup_heartbeat ()
 
bool setup_nodes ()
 
bool setup_sync ()
 
- Protected Member Functions inherited from LayerGroup<>
void call_or_fail (FuncType func, FailType fail, Data &status)
 
void call_or_fail_rev (FuncType func, FailType fail, Data &status)
 
virtual void handleDiag (LayerReport &report)
 
virtual void handleHalt (LayerStatus &status)
 
virtual void handleInit (LayerStatus &status)
 
virtual void handleRead (LayerStatus &status, const LayerState &current_state)
 
virtual void handleRecover (LayerStatus &status)
 
virtual void handleShutdown (LayerStatus &status)
 
virtual void handleWrite (LayerStatus &status, const LayerState &current_state)
 
- Protected Member Functions inherited from canopen::Layer
virtual void handleDiag (LayerReport &report)=0
 
virtual void handleHalt (LayerStatus &status)=0
 
virtual void handleInit (LayerStatus &status)=0
 
virtual void handleRead (LayerStatus &status, const LayerState &current_state)=0
 
virtual void handleRecover (LayerStatus &status)=0
 
- Protected Member Functions inherited from VectorHelper< Layer >
vector_type::iterator call (FuncType func, Data &status)
 
vector_type::iterator call (FuncType func, Data &status)
 
vector_type::reverse_iterator call_rev (FuncType func, Data &status)
 
vector_type::reverse_iterator call_rev (FuncType func, Data &status)
 
void destroy ()
 
- Protected Attributes inherited from canopen::RosChain
boost::mutex diag_mutex_
 
ros::Timer diag_timer_
 
diagnostic_updater::Updater diag_updater_
 
boost::shared_ptr< canopen::LayerGroupNoDiag< canopen::EMCYHandler > > emcy_handlers_
 
struct canopen::RosChain::HeartbeatSender hb_sender_
 
Timer heartbeat_timer_
 
can::DriverInterfaceSharedPtr interface_
 
std::vector< LoggerSharedPtrloggers_
 
MasterSharedPtr master_
 
boost::mutex mutex_
 
ros::NodeHandle nh_
 
ros::NodeHandle nh_priv_
 
boost::shared_ptr< canopen::LayerGroupNoDiag< canopen::Node > > nodes_
 
std::map< std::string, canopen::NodeSharedPtrnodes_lookup_
 
std::vector< PublishFunc::FuncTypepublishers_
 
bool reset_errors_before_recover_
 
boost::atomic< bool > running_
 
ros::ServiceServer srv_get_object_
 
ros::ServiceServer srv_halt_
 
ros::ServiceServer srv_init_
 
ros::ServiceServer srv_recover_
 
ros::ServiceServer srv_set_object_
 
ros::ServiceServer srv_shutdown_
 
can::StateListenerConstSharedPtr state_listener_
 
canopen::SyncLayerSharedPtr sync_
 
boost::scoped_ptr< boost::thread > thread_
 
time_duration update_duration_
 

Detailed Description

Definition at line 15 of file motor_chain.h.

Constructor & Destructor Documentation

MotorChain::MotorChain ( const ros::NodeHandle nh,
const ros::NodeHandle nh_priv 
)

Definition at line 28 of file motor_chain.cpp.

Member Function Documentation

bool MotorChain::nodeAdded ( XmlRpc::XmlRpcValue params,
const canopen::NodeSharedPtr node,
const LoggerSharedPtr logger 
)
privatevirtual

Reimplemented from canopen::RosChain.

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.

Member Data Documentation

boost::shared_ptr<ControllerManagerLayer> canopen::MotorChain::cm_
private

Definition at line 20 of file motor_chain.h.

ClassAllocator<canopen::MotorBase> canopen::MotorChain::motor_allocator_
private

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.

RobotLayerSharedPtr canopen::MotorChain::robot_layer_
private

Definition at line 18 of file motor_chain.h.


The documentation for this class was generated from the following files:


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Fri May 14 2021 02:59:45