sync_node.cpp
Go to the documentation of this file.
4 #include <ros/ros.h>
6 
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();
11  sstr << *it;
12  for(++it; it != container.end(); ++it){
13  sstr << delim << *it;
14  }
15  return sstr.str();
16 }
19  sync.read(r);
20  sync.diag(r);
22  stat.summary(r.get(), r.reason());
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);
25  }
28  sync.recover(s);
29  }
30  }else{
31  stat.summary(stat.WARN, "sync not initilized");
33  sync.init(s);
34  }
35 }
36 
37 int main(int argc, char** argv){
38  ros::init(argc, argv, "canopen_sync_node");
39 
40  ros::NodeHandle nh;
41  ros::NodeHandle nh_priv("~");
42 
43  ros::NodeHandle sync_nh(nh_priv, "sync");
44  int sync_ms;
45  if(!sync_nh.getParam("interval_ms", sync_ms) || sync_ms <=0){
46  ROS_ERROR_STREAM("Sync interval "<< sync_ms << " is invalid");
47  return 1;
48  }
49 
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");
53  }
54  if(sync_overflow == 1 || sync_overflow > 240){
55  ROS_ERROR_STREAM("Sync overflow "<< sync_overflow << " is invalid");
56  return 1;
57  }
58 
59 
60  std::string can_device;
61  if(!nh_priv.getParam("bus/device",can_device)){
62  ROS_ERROR("Device not set");
63  return 1;
64  }
65 
66  can::SocketCANDriverSharedPtr driver = boost::make_shared<can::SocketCANDriver>();
67  canopen::SyncProperties sync_properties(can::MsgHeader(sync_nh.param("sync_id", 0x080)), sync_ms, sync_overflow);
68 
69  boost::shared_ptr<canopen::BCMsync> sync = boost::make_shared<canopen::BCMsync>(can_device, driver, sync_properties);
70 
71  std::vector<int> nodes;
72 
73  if(sync_nh.getParam("monitored_nodes",nodes)){
74  sync->setMonitored(nodes);
75  }else{
76  std::string msg;
77  if(nh_priv.getParam("heartbeat/msg", msg)){
78  can::Frame f = can::toframe(msg);
79  if(f.isValid() && (f.id & ~canopen::BCMsync::ALL_NODES_MASK) == canopen::BCMsync::HEARTBEAT_ID){
80  nodes.push_back(f.id & canopen::BCMsync::ALL_NODES_MASK);
81  }
82  }
83  sync_nh.getParam("ignored_nodes",nodes);
84  sync->setIgnored(nodes);
85  }
86 
87  canopen::LayerStack stack("SyncNodeLayer");
88 
89  stack.add(boost::make_shared<canopen::CANLayer>(driver, can_device, false));
90  stack.add(sync);
91 
92  diagnostic_updater::Updater diag_updater(nh, nh_priv);
93  diag_updater.setHardwareID(nh_priv.param("hardware_id", std::string("none")));
94  diag_updater.add("sync", boost::bind(report_diagnostics,boost::ref(stack), _1));
95 
96  ros::Timer diag_timer = nh.createTimer(ros::Duration(diag_updater.getPeriod()/2.0),boost::bind(&diagnostic_updater::Updater::update, &diag_updater));
97 
98  ros::spin();
99  return 0;
100 }
msg
virtual void add(const VectorMemberSharedPtr &l)
void init(LayerStatus &status)
f
void summary(unsigned char lvl, const std::string s)
void read(LayerStatus &status)
int main(int argc, char **argv)
Definition: sync_node.cpp:37
void setHardwareID(const std::string &hwid)
XmlRpcServer s
std::string join(const T &container, const std::string &delim)
Definition: sync_node.cpp:7
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)
#define ROS_WARN(...)
Frame toframe(const std::string &s)
static const uint32_t ALL_NODES_MASK
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
LayerState getLayerState()
ROSCPP_DECL void spin()
const std::vector< std::pair< std::string, std::string > > & values() const
void report_diagnostics(canopen::LayerStack &sync, diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: sync_node.cpp:17
bool isValid() const
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)
unsigned int id
#define ROS_ERROR(...)
bool bounded() const
static const uint32_t HEARTBEAT_ID


canopen_chain_node
Author(s): Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:46