Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
canopen::RosChain Class Reference

#include <ros_chain.h>

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

Classes

struct  HeartbeatSender
 

Public Member Functions

 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)
 

Protected Member Functions

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)
 
virtual bool nodeAdded (XmlRpc::XmlRpcValue &params, const canopen::NodeSharedPtr &node, const LoggerSharedPtr &logger)
 
void report_diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void run ()
 
bool setup_bus ()
 
virtual bool setup_chain ()
 
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

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_
 

Private Attributes

GuardedClassLoader< can::DriverInterfacedriver_loader_
 
ClassAllocator< canopen::Mastermaster_allocator_
 

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
 
- Private Types inherited from canopen::GuardedClassLoaderList
typedef boost::shared_ptr< pluginlib::ClassLoaderBaseClassLoaderBaseSharedPtr
 
- Private Member Functions inherited from canopen::GuardedClassLoaderList
 ~GuardedClassLoaderList ()
 
- Static Private Member Functions inherited from canopen::GuardedClassLoaderList
static void addLoader (ClassLoaderBaseSharedPtr b)
 

Detailed Description

Definition at line 160 of file ros_chain.h.

Constructor & Destructor Documentation

canopen::RosChain::RosChain ( const ros::NodeHandle nh,
const ros::NodeHandle nh_priv 
)

Definition at line 533 of file ros_chain.cpp.

canopen::RosChain::~RosChain ( )
virtual

Definition at line 571 of file ros_chain.cpp.

Member Function Documentation

bool canopen::RosChain::handle_get_object ( canopen_chain_node::GetObject::Request &  req,
canopen_chain_node::GetObject::Response &  res 
)
protected

Definition at line 188 of file ros_chain.cpp.

bool canopen::RosChain::handle_halt ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
protectedvirtual

Definition at line 175 of file ros_chain.cpp.

bool canopen::RosChain::handle_init ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
protectedvirtual

Definition at line 73 of file ros_chain.cpp.

bool canopen::RosChain::handle_recover ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
protectedvirtual

Definition at line 111 of file ros_chain.cpp.

bool canopen::RosChain::handle_set_object ( canopen_chain_node::SetObject::Request &  req,
canopen_chain_node::SetObject::Response &  res 
)
protected

Definition at line 203 of file ros_chain.cpp.

bool canopen::RosChain::handle_shutdown ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
protectedvirtual

Definition at line 161 of file ros_chain.cpp.

void canopen::RosChain::handleShutdown ( LayerStatus status)
protectedvirtual

Reimplemented from canopen::LayerStack.

Definition at line 149 of file ros_chain.cpp.

void canopen::RosChain::handleWrite ( LayerStatus status,
const LayerState current_state 
)
protectedvirtual

Reimplemented from canopen::LayerStack.

Definition at line 142 of file ros_chain.cpp.

void canopen::RosChain::logState ( const can::State s)
protected

Definition at line 45 of file ros_chain.cpp.

bool canopen::RosChain::nodeAdded ( XmlRpc::XmlRpcValue params,
const canopen::NodeSharedPtr node,
const LoggerSharedPtr logger 
)
protectedvirtual

Definition at line 511 of file ros_chain.cpp.

void canopen::RosChain::report_diagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
protected

Definition at line 515 of file ros_chain.cpp.

void canopen::RosChain::run ( )
protected

Definition at line 52 of file ros_chain.cpp.

bool canopen::RosChain::setup ( )

Definition at line 541 of file ros_chain.cpp.

bool canopen::RosChain::setup_bus ( )
protected

Definition at line 218 of file ros_chain.cpp.

bool canopen::RosChain::setup_chain ( )
protectedvirtual

Definition at line 548 of file ros_chain.cpp.

bool canopen::RosChain::setup_heartbeat ( )
protected

Definition at line 319 of file ros_chain.cpp.

bool canopen::RosChain::setup_nodes ( )
protected

Definition at line 378 of file ros_chain.cpp.

bool canopen::RosChain::setup_sync ( )
protected

Definition at line 271 of file ros_chain.cpp.

Member Data Documentation

boost::mutex canopen::RosChain::diag_mutex_
protected

Definition at line 203 of file ros_chain.h.

ros::Timer canopen::RosChain::diag_timer_
protected

Definition at line 181 of file ros_chain.h.

diagnostic_updater::Updater canopen::RosChain::diag_updater_
protected

Definition at line 180 of file ros_chain.h.

GuardedClassLoader<can::DriverInterface> canopen::RosChain::driver_loader_
private

Definition at line 161 of file ros_chain.h.

boost::shared_ptr<canopen::LayerGroupNoDiag<canopen::EMCYHandler> > canopen::RosChain::emcy_handlers_
protected

Definition at line 167 of file ros_chain.h.

struct canopen::RosChain::HeartbeatSender canopen::RosChain::hb_sender_
protected
Timer canopen::RosChain::heartbeat_timer_
protected

Definition at line 200 of file ros_chain.h.

can::DriverInterfaceSharedPtr canopen::RosChain::interface_
protected

Definition at line 164 of file ros_chain.h.

std::vector<LoggerSharedPtr > canopen::RosChain::loggers_
protected

Definition at line 170 of file ros_chain.h.

MasterSharedPtr canopen::RosChain::master_
protected

Definition at line 165 of file ros_chain.h.

ClassAllocator<canopen::Master> canopen::RosChain::master_allocator_
private

Definition at line 162 of file ros_chain.h.

boost::mutex canopen::RosChain::mutex_
protected

Definition at line 183 of file ros_chain.h.

ros::NodeHandle canopen::RosChain::nh_
protected

Definition at line 177 of file ros_chain.h.

ros::NodeHandle canopen::RosChain::nh_priv_
protected

Definition at line 178 of file ros_chain.h.

boost::shared_ptr<canopen::LayerGroupNoDiag<canopen::Node> > canopen::RosChain::nodes_
protected

Definition at line 166 of file ros_chain.h.

std::map<std::string, canopen::NodeSharedPtr > canopen::RosChain::nodes_lookup_
protected

Definition at line 168 of file ros_chain.h.

std::vector<PublishFunc::FuncType> canopen::RosChain::publishers_
protected

Definition at line 171 of file ros_chain.h.

bool canopen::RosChain::reset_errors_before_recover_
protected

Definition at line 205 of file ros_chain.h.

boost::atomic<bool> canopen::RosChain::running_
protected

Definition at line 202 of file ros_chain.h.

ros::ServiceServer canopen::RosChain::srv_get_object_
protected

Definition at line 188 of file ros_chain.h.

ros::ServiceServer canopen::RosChain::srv_halt_
protected

Definition at line 186 of file ros_chain.h.

ros::ServiceServer canopen::RosChain::srv_init_
protected

Definition at line 184 of file ros_chain.h.

ros::ServiceServer canopen::RosChain::srv_recover_
protected

Definition at line 185 of file ros_chain.h.

ros::ServiceServer canopen::RosChain::srv_set_object_
protected

Definition at line 189 of file ros_chain.h.

ros::ServiceServer canopen::RosChain::srv_shutdown_
protected

Definition at line 187 of file ros_chain.h.

can::StateListenerConstSharedPtr canopen::RosChain::state_listener_
protected

Definition at line 173 of file ros_chain.h.

canopen::SyncLayerSharedPtr canopen::RosChain::sync_
protected

Definition at line 169 of file ros_chain.h.

boost::scoped_ptr<boost::thread> canopen::RosChain::thread_
protected

Definition at line 175 of file ros_chain.h.

time_duration canopen::RosChain::update_duration_
protected

Definition at line 191 of file ros_chain.h.


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


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