#include <ros_chain.h>
Public Types | |
typedef boost::function< void()> | func_type |
Static Public Member Functions | |
static func_type | create (ros::NodeHandle &nh, const std::string &name, boost::shared_ptr< canopen::Node > node, const std::string &key, bool force) |
Static Private Member Functions | |
template<typename Tpub , typename Tobj > | |
static func_type | create (ros::NodeHandle &nh, const std::string &name, ObjectStorage::Entry< Tobj > entry, bool force) |
template<typename Tpub , typename Tobj , bool forced> | |
static void | publish (ros::Publisher &pub, ObjectStorage::Entry< Tobj > &entry) |
Definition at line 19 of file ros_chain.h.
typedef boost::function<void()> canopen::PublishFunc::func_type |
Definition at line 21 of file ros_chain.h.
PublishFunc::func_type canopen::PublishFunc::create | ( | ros::NodeHandle & | nh, |
const std::string & | name, | ||
boost::shared_ptr< canopen::Node > | node, | ||
const std::string & | key, | ||
bool | force | ||
) | [static] |
Definition at line 19 of file ros_chain.cpp.
static func_type canopen::PublishFunc::create | ( | ros::NodeHandle & | nh, |
const std::string & | name, | ||
ObjectStorage::Entry< Tobj > | entry, | ||
bool | force | ||
) | [inline, static, private] |
Definition at line 30 of file ros_chain.h.
static void canopen::PublishFunc::publish | ( | ros::Publisher & | pub, |
ObjectStorage::Entry< Tobj > & | entry | ||
) | [inline, static, private] |
Definition at line 25 of file ros_chain.h.