#include <ros_chain.h>

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 ¤t_state) |
| void | logState (const can::State &s) |
| virtual bool | nodeAdded (XmlRpc::XmlRpcValue ¶ms, 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 ¤t_state) |
| virtual void | handleRecover (LayerStatus &status) |
| virtual void | handleShutdown (LayerStatus &status) |
| virtual void | handleWrite (LayerStatus &status, const LayerState ¤t_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 ¤t_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 () |
Private Attributes | |
| GuardedClassLoader< can::DriverInterface > | driver_loader_ |
| ClassAllocator< canopen::Master > | master_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< VectorMemberSharedPtr > | vector_type |
Private Types inherited from canopen::GuardedClassLoaderList | |
| typedef boost::shared_ptr< pluginlib::ClassLoaderBase > | ClassLoaderBaseSharedPtr |
Private Member Functions inherited from canopen::GuardedClassLoaderList | |
| ~GuardedClassLoaderList () | |
Static Private Member Functions inherited from canopen::GuardedClassLoaderList | |
| static void | addLoader (ClassLoaderBaseSharedPtr b) |
Definition at line 160 of file ros_chain.h.
| canopen::RosChain::RosChain | ( | const ros::NodeHandle & | nh, |
| const ros::NodeHandle & | nh_priv | ||
| ) |
Definition at line 533 of file ros_chain.cpp.
|
virtual |
Definition at line 571 of file ros_chain.cpp.
|
protected |
Definition at line 188 of file ros_chain.cpp.
|
protectedvirtual |
Definition at line 175 of file ros_chain.cpp.
|
protectedvirtual |
Definition at line 73 of file ros_chain.cpp.
|
protectedvirtual |
Definition at line 111 of file ros_chain.cpp.
|
protected |
Definition at line 203 of file ros_chain.cpp.
|
protectedvirtual |
Definition at line 161 of file ros_chain.cpp.
|
protectedvirtual |
Reimplemented from canopen::LayerStack.
Definition at line 149 of file ros_chain.cpp.
|
protectedvirtual |
Reimplemented from canopen::LayerStack.
Definition at line 142 of file ros_chain.cpp.
|
protected |
Definition at line 45 of file ros_chain.cpp.
|
protectedvirtual |
Definition at line 511 of file ros_chain.cpp.
|
protected |
Definition at line 515 of file ros_chain.cpp.
|
protected |
Definition at line 52 of file ros_chain.cpp.
| bool canopen::RosChain::setup | ( | ) |
Definition at line 541 of file ros_chain.cpp.
|
protected |
Definition at line 218 of file ros_chain.cpp.
|
protectedvirtual |
Definition at line 548 of file ros_chain.cpp.
|
protected |
Definition at line 319 of file ros_chain.cpp.
|
protected |
Definition at line 378 of file ros_chain.cpp.
|
protected |
Definition at line 271 of file ros_chain.cpp.
|
protected |
Definition at line 203 of file ros_chain.h.
|
protected |
Definition at line 181 of file ros_chain.h.
|
protected |
Definition at line 180 of file ros_chain.h.
|
private |
Definition at line 161 of file ros_chain.h.
|
protected |
Definition at line 167 of file ros_chain.h.
|
protected |
|
protected |
Definition at line 200 of file ros_chain.h.
|
protected |
Definition at line 164 of file ros_chain.h.
|
protected |
Definition at line 170 of file ros_chain.h.
|
protected |
Definition at line 165 of file ros_chain.h.
|
private |
Definition at line 162 of file ros_chain.h.
|
protected |
Definition at line 183 of file ros_chain.h.
|
protected |
Definition at line 177 of file ros_chain.h.
|
protected |
Definition at line 178 of file ros_chain.h.
|
protected |
Definition at line 166 of file ros_chain.h.
|
protected |
Definition at line 168 of file ros_chain.h.
|
protected |
Definition at line 171 of file ros_chain.h.
|
protected |
Definition at line 205 of file ros_chain.h.
|
protected |
Definition at line 202 of file ros_chain.h.
|
protected |
Definition at line 188 of file ros_chain.h.
|
protected |
Definition at line 186 of file ros_chain.h.
|
protected |
Definition at line 184 of file ros_chain.h.
|
protected |
Definition at line 185 of file ros_chain.h.
|
protected |
Definition at line 189 of file ros_chain.h.
|
protected |
Definition at line 187 of file ros_chain.h.
|
protected |
Definition at line 173 of file ros_chain.h.
|
protected |
Definition at line 169 of file ros_chain.h.
|
protected |
Definition at line 175 of file ros_chain.h.
|
protected |
Definition at line 191 of file ros_chain.h.