7 template<
typename T > std::string 
join(
const T &container, 
const std::string &delim){
     8     if(container.empty()) 
return std::string();
     9     std::stringstream sstr;
    10     typename T::const_iterator it = container.begin();
    12     for(++it; it != container.end(); ++it){
    23         for(std::vector<std::pair<std::string, std::string> >::const_iterator it = r.
values().begin(); it != r.
values().end(); ++it){
    24             stat.
add(it->first, it->second);
    31         stat.
summary(stat.WARN, 
"sync not initilized");
    37 int main(
int argc, 
char** argv){
    38     ros::init(argc, argv, 
"canopen_sync_node");
    45     if(!sync_nh.
getParam(
"interval_ms", sync_ms) || sync_ms <=0){
    50     int sync_overflow = 0;
    51     if(!sync_nh.
getParam(
"overflow", sync_overflow)){
    52         ROS_WARN(
"Sync overflow was not specified, so overflow is disabled per default");
    54     if(sync_overflow == 1 || sync_overflow > 240){
    60     std::string can_device;
    61     if(!nh_priv.
getParam(
"bus/device",can_device)){
    71     std::vector<int> nodes;
    73     if(sync_nh.
getParam(
"monitored_nodes",nodes)){
    74         sync->setMonitored(nodes);
    77         if(nh_priv.
getParam(
"heartbeat/msg", msg)){
    83         sync_nh.
getParam(
"ignored_nodes",nodes);
    84         sync->setIgnored(nodes);
    89     stack.
add(boost::make_shared<canopen::CANLayer>(driver, can_device, 
false));
 
virtual void add(const VectorMemberSharedPtr &l)
void init(LayerStatus &status)
void summary(unsigned char lvl, const std::string s)
void read(LayerStatus &status)
int main(int argc, char **argv)
void setHardwareID(const std::string &hwid)
std::string join(const T &container, const std::string &delim)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void add(const std::string &name, TaskFunction f)
const std::string reason() const 
void recover(LayerStatus &status)
Frame toframe(const std::string &s)
static const uint32_t ALL_NODES_MASK
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
LayerState getLayerState()
const std::vector< std::pair< std::string, std::string > > & values() const 
void report_diagnostics(canopen::LayerStack &sync, diagnostic_updater::DiagnosticStatusWrapper &stat)
bool getParam(const std::string &key, std::string &s) const 
void diag(LayerReport &report)
void add(const std::string &key, const T &val)
#define ROS_ERROR_STREAM(args)
static const uint32_t HEARTBEAT_ID