Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes
canopen::RosChain Class Reference

#include <ros_chain.h>

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

List of all members.

Classes

struct  HeartbeatSender

Public Member Functions

 RosChain (const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv)
bool setup ()
virtual ~RosChain ()

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 boost::shared_ptr< canopen::Node > &node, const boost::shared_ptr< Logger > &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 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_
boost::shared_ptr
< can::DriverInterface
interface_
std::vector< boost::shared_ptr
< Logger > > 
loggers_
boost::shared_ptr< Mastermaster_
boost::mutex mutex_
ros::NodeHandle nh_
ros::NodeHandle nh_priv_
boost::shared_ptr
< canopen::LayerGroupNoDiag
< canopen::Node > > 
nodes_
std::map< std::string,
boost::shared_ptr
< canopen::Node > > 
nodes_lookup_
std::vector
< PublishFunc::func_type
publishers_
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::StateInterface::StateListener::Ptr state_listener_
boost::shared_ptr
< canopen::SyncLayer
sync_
boost::scoped_ptr< boost::thread > thread_
time_duration update_duration_

Private Attributes

GuardedClassLoader
< can::DriverInterface
driver_loader_
ClassAllocator< canopen::Mastermaster_allocator_

Detailed Description

Definition at line 154 of file ros_chain.h.


Constructor & Destructor Documentation

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

Definition at line 536 of file ros_chain.cpp.

Definition at line 574 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 
) [protected, virtual]

Definition at line 175 of file ros_chain.cpp.

bool canopen::RosChain::handle_init ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
) [protected, virtual]

Definition at line 73 of file ros_chain.cpp.

bool canopen::RosChain::handle_recover ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
) [protected, virtual]

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 
) [protected, virtual]

Definition at line 161 of file ros_chain.cpp.

void canopen::RosChain::handleShutdown ( LayerStatus status) [protected, virtual]

Reimplemented from canopen::LayerStack.

Definition at line 149 of file ros_chain.cpp.

void canopen::RosChain::handleWrite ( LayerStatus status,
const LayerState current_state 
) [protected, virtual]

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 boost::shared_ptr< canopen::Node > &  node,
const boost::shared_ptr< Logger > &  logger 
) [protected, virtual]

Definition at line 514 of file ros_chain.cpp.

Definition at line 518 of file ros_chain.cpp.

void canopen::RosChain::run ( ) [protected]

Definition at line 52 of file ros_chain.cpp.

Definition at line 544 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 ( ) [protected, virtual]

Definition at line 551 of file ros_chain.cpp.

bool canopen::RosChain::setup_heartbeat ( ) [protected]

Definition at line 322 of file ros_chain.cpp.

bool canopen::RosChain::setup_nodes ( ) [protected]

Definition at line 381 of file ros_chain.cpp.

bool canopen::RosChain::setup_sync ( ) [protected]

Definition at line 274 of file ros_chain.cpp.


Member Data Documentation

boost::mutex canopen::RosChain::diag_mutex_ [protected]

Definition at line 197 of file ros_chain.h.

Definition at line 175 of file ros_chain.h.

Definition at line 174 of file ros_chain.h.

Definition at line 155 of file ros_chain.h.

Definition at line 161 of file ros_chain.h.

Definition at line 194 of file ros_chain.h.

boost::shared_ptr<can::DriverInterface> canopen::RosChain::interface_ [protected]

Definition at line 158 of file ros_chain.h.

std::vector<boost::shared_ptr<Logger > > canopen::RosChain::loggers_ [protected]

Definition at line 164 of file ros_chain.h.

boost::shared_ptr<Master> canopen::RosChain::master_ [protected]

Definition at line 159 of file ros_chain.h.

Definition at line 156 of file ros_chain.h.

boost::mutex canopen::RosChain::mutex_ [protected]

Definition at line 177 of file ros_chain.h.

Definition at line 171 of file ros_chain.h.

Definition at line 172 of file ros_chain.h.

Definition at line 160 of file ros_chain.h.

std::map<std::string, boost::shared_ptr<canopen::Node> > canopen::RosChain::nodes_lookup_ [protected]

Definition at line 162 of file ros_chain.h.

Definition at line 165 of file ros_chain.h.

Definition at line 199 of file ros_chain.h.

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

Definition at line 196 of file ros_chain.h.

Definition at line 182 of file ros_chain.h.

Definition at line 180 of file ros_chain.h.

Definition at line 178 of file ros_chain.h.

Definition at line 179 of file ros_chain.h.

Definition at line 183 of file ros_chain.h.

Definition at line 181 of file ros_chain.h.

Definition at line 167 of file ros_chain.h.

boost::shared_ptr<canopen::SyncLayer> canopen::RosChain::sync_ [protected]

Definition at line 163 of file ros_chain.h.

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

Definition at line 169 of file ros_chain.h.

Definition at line 185 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 Sun Sep 3 2017 03:10:52