10 template<
typename T > std::string
join(
const T &container,
const std::string &delim){
11 if(container.empty())
return std::string();
12 std::stringstream sstr;
13 typename T::const_iterator it = container.begin();
15 for(++it; it != container.end(); ++it){
40 if(ignored_nodes_.find(
id) != ignored_nodes_.end())
return true;
41 if(!monitored_nodes_.empty() && monitored_nodes_.find(
id) == monitored_nodes_.end())
return true;
42 known_nodes_.insert(
id);
47 boost::mutex::scoped_lock lock(mutex_);
52 uint8_t
id = frame.
data[1];
56 if(
id != 0) started_nodes_.insert(
id);
57 else started_nodes_.insert(known_nodes_.begin(), known_nodes_.end());
59 if(
id != 0) started_nodes_.erase(
id);
60 else started_nodes_.clear();
72 sync_running_ = !bcm_.
stopTX(sync_frames_.front());
74 sync_running_ = bcm_.
startTX(boost::chrono::milliseconds(sync_ms_),sync_frames_.front(), sync_frames_.size(), &sync_frames_[0]);
79 if(current_state >
Init){
83 if(current_state >
Init){
87 boost::mutex::scoped_lock lock(mutex_);
88 if(!sync_running_) report.
warn(
"sync is not running");
90 report.
add(
"sync_running", sync_running_);
91 report.
add(
"known_nodes",
join(known_nodes_,
", "));
92 report.
add(
"started_nodes",
join(started_nodes_,
", "));
96 boost::mutex::scoped_lock lock(mutex_);
97 started_nodes_.clear();
99 if(!bcm_.
init(device_)){
100 status.
error(
"BCM_init failed");
103 int sc = driver_->getInternalSocket();
105 struct can_filter filter[2];
107 filter[0].can_id =
NMT_ID;
108 filter[0].can_mask = CAN_SFF_MASK;
112 if(setsockopt(sc, SOL_CAN_RAW, CAN_RAW_FILTER, &filter,
sizeof(filter)) < 0){
113 status.
warn(
"could not set filter");
120 boost::mutex::scoped_lock lock(mutex_);
126 boost::mutex::scoped_lock lock(mutex_);
128 bcm_.
stopTX(sync_frames_.front());
129 sync_running_ =
false;
130 started_nodes_.clear();
144 :
Layer(device +
" SyncLayer"), device_(device), sync_running_(false), sync_ms_(sync_properties.period_ms_), driver_(driver) {
146 sync_frames_.resize(1);
149 sync_frames_.resize(sync_properties.
overflow_);
150 for(
int i = 0; i < sync_properties.
overflow_; ++i){
152 sync_frames_[i].data[0] = i+1;
157 monitored_nodes_.clear();
158 monitored_nodes_.insert(other.begin(), other.end());
161 ignored_nodes_.clear();
162 ignored_nodes_.insert(other.begin(), other.end());
bool stopTX(Header header)
std::set< int > known_nodes_
virtual void handleRecover(LayerStatus &status)
const void warn(const std::string &r)
const can::Header header_
virtual void handleInit(LayerStatus &status)
virtual void handleDiag(LayerReport &report)
virtual void handleShutdown(LayerStatus &status)
void handleFrame(const can::Frame &frame)
boost::array< value_type, 8 > data
void setMonitored(const T &other)
void setIgnored(const T &other)
static const uint32_t NMT_ID
BCMsync(const std::string &device, can::SocketCANDriverSharedPtr driver, const SyncProperties &sync_properties)
static const uint32_t ALL_NODES_MASK
virtual void handleHalt(LayerStatus &status)
std::set< int > started_nodes_
CommInterface::FrameListenerConstSharedPtr FrameListenerConstSharedPtr
std::vector< can::Frame > sync_frames_
bool init(const std::string &device)
can::FrameListenerConstSharedPtr handler_
void add(const std::string &key, const T &value)
std::set< int > ignored_nodes_
const void error(const std::string &r)
bool startTX(DurationType period, Header header, size_t num, Frame *frames)
virtual void handleWrite(LayerStatus &status, const LayerState ¤t_state)
boost::shared_ptr< SocketCANDriver > SocketCANDriverSharedPtr
bool skipNode(uint8_t id)
std::set< int > monitored_nodes_
virtual void handleRead(LayerStatus &status, const LayerState ¤t_state)
std::string join(const T &container, const std::string &delim)
can::SocketCANDriverSharedPtr driver_
static const uint32_t HEARTBEAT_ID