PdsNode.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017-2018, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include "PdsNode.h"
36 
37 namespace dataspeed_pds_lcm
38 {
39 
40 PdsNode::PdsNode(ros::NodeHandle &nh, ros::NodeHandle &priv_nh, lcm::LCM *lcm)
41 {
42  // Setup message synchronizers
46  sync_ros_slave1_->registerCallback(boost::bind(&PdsNode::recvSyncSlave1, this, _1, _2));
47  sync_ros_slave2_->registerCallback(boost::bind(&PdsNode::recvSyncSlave2, this, _1, _2, _3));
48  sync_ros_slave3_->registerCallback(boost::bind(&PdsNode::recvSyncSlave3, this, _1, _2, _3, _4));
49 
50  // Reduce synchronization delay
51  const ros::Duration SYNC_20_MS(0.006); // 30% of 20ms period
52  sync_ros_slave1_->setInterMessageLowerBound(0, SYNC_20_MS);
53  sync_ros_slave1_->setInterMessageLowerBound(1, SYNC_20_MS);
54  sync_ros_slave2_->setInterMessageLowerBound(0, SYNC_20_MS);
55  sync_ros_slave2_->setInterMessageLowerBound(1, SYNC_20_MS);
56  sync_ros_slave2_->setInterMessageLowerBound(2, SYNC_20_MS);
57  sync_ros_slave3_->setInterMessageLowerBound(0, SYNC_20_MS);
58  sync_ros_slave3_->setInterMessageLowerBound(1, SYNC_20_MS);
59  sync_ros_slave3_->setInterMessageLowerBound(2, SYNC_20_MS);
60  sync_ros_slave3_->setInterMessageLowerBound(3, SYNC_20_MS);
61 
62  // Setup Publishers
63  pub_status_ = nh.advertise<dataspeed_pds_msgs::Status>("status", 10);
64 
65  // Setup Subscribers
66  sub_relay_ = nh.subscribe("relay", 10, &PdsNode::recvRelay, this, ros::TransportHints().tcpNoDelay(true));
67  sub_mode_ = nh.subscribe("mode", 10, &PdsNode::recvMode, this, ros::TransportHints().tcpNoDelay(true));
68  sub_script_ = nh.subscribe("script", 10, &PdsNode::recvScript, this, ros::TransportHints().tcpNoDelay(true));
69 
70  // Hold onto the LCM handle
71  lcm_ = *lcm;
72 
73  // LCM Subscribers
74  lcm_.subscribe("STATUS", &PdsNode::lcmRecvStatus, this);
75 }
77 {
78  if (sync_ros_slave1_) {
79  delete sync_ros_slave1_;
80  sync_ros_slave1_ = NULL;
81  }
82  if (sync_ros_slave2_) {
83  delete sync_ros_slave2_;
84  sync_ros_slave2_ = NULL;
85  }
86  if (sync_ros_slave3_) {
87  delete sync_ros_slave3_;
88  sync_ros_slave3_ = NULL;
89  }
90 }
91 
92 void PdsNode::lcmRecvStatus(const lcm::ReceiveBuffer* buf, const std::string &chan, const status_t *lcm) {
93 #if 0
94  ROS_INFO("Received LCM message from channel '%s'", chan.c_str());
95 #endif
96 
97  // Timestamp
98  const ros::Time now = ros::Time::now();
99 
100  // Convert to ROS message
101  dataspeed_pds_msgs::Status msg;
102  msg.header.stamp = now;
103  msg.mode.mode = lcm->mode;
104  msg.script.script = 0;
105  msg.chan.resize(12);
106  for (size_t i = 0; i < 12; i++) {
107  msg.chan[i].current = lcm->current[i];
108  msg.chan[i].status = lcm->status[i];
109  }
110  msg.master.inverter.request = (lcm->inverter_status & (1 << 0)) ? true : false;
111  msg.master.inverter.status = (lcm->inverter_status & (1 << 1)) ? true : false;
112  msg.master.inverter.overload = (lcm->inverter_status & (1 << 2)) ? true : false;
113  msg.master.inverter.overtemp = (lcm->inverter_status & (1 << 3)) ? true : false;
114  msg.master.temp.internal = lcm->board_temp;
115  msg.master.temp.external = lcm->thermocouple;
116  msg.master.voltage = lcm->voltage;
117 
118  // Publish for single unit, or forward to multi-unit synchronization
119  const dataspeed_pds_msgs::Status::ConstPtr ptr(new dataspeed_pds_msgs::Status(msg));
120  switch (lcm->unit_id) {
121  case MASTER:
122  sync_msg_master_.add(ptr);
123  if ((now - stamp_slave1_) > TIMEOUT) {
124  pub_status_.publish(msg);
125  }
126  break;
127  case SLAVE1:
128  stamp_slave1_ = now;
129  sync_msg_slave1_.add(ptr);
130  break;
131  case SLAVE2:
132  stamp_slave2_ = now;
133  sync_msg_slave2_.add(ptr);
134  break;
135  case SLAVE3:
136  stamp_slave3_ = now;
137  sync_msg_slave3_.add(ptr);
138  break;
139  }
140 }
141 
142 void PdsNode::recvRelay(const dataspeed_pds_msgs::Relay::ConstPtr &msg)
143 {
144  relay_request_t out;
145  out.channel = msg->channel;
146  out.request = msg->request;
147  lcm_.publish("RELAY", &out);
148 }
149 
150 void PdsNode::recvMode(const dataspeed_pds_msgs::Mode::ConstPtr &msg)
151 {
152  mode_t out;
153  out.mode = msg->mode;
154  lcm_.publish("MODE", &out);
155 }
156 
157 void PdsNode::recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg)
158 {
159  script_request_t out;
160  out.script = msg->script;
161  lcm_.publish("SCRIPT", &out);
162 }
163 
164 void PdsNode::recvSyncSlave1(const SyncPtr& master, const SyncPtr& slave1)
165 {
166  if ((ros::Time::now() - stamp_slave2_) > TIMEOUT) {
167  dataspeed_pds_msgs::Status msg = *master;
168  msg.chan.insert(msg.chan.end(), slave1->chan.begin(), slave1->chan.end());
169  msg.slave.push_back(slave1->master);
170  pub_status_.publish(msg);
171  }
172 }
173 void PdsNode::recvSyncSlave2(const SyncPtr& master, const SyncPtr& slave1, const SyncPtr& slave2)
174 {
175  if ((ros::Time::now() - stamp_slave3_) > TIMEOUT) {
176  dataspeed_pds_msgs::Status msg = *master;
177  msg.chan.insert(msg.chan.end(), slave1->chan.begin(), slave1->chan.end());
178  msg.chan.insert(msg.chan.end(), slave2->chan.begin(), slave2->chan.end());
179  msg.slave.push_back(slave1->master);
180  msg.slave.push_back(slave2->master);
181  pub_status_.publish(msg);
182  }
183 }
184 void PdsNode::recvSyncSlave3(const SyncPtr& master, const SyncPtr& slave1, const SyncPtr& slave2, const SyncPtr& slave3)
185 {
186  if (1) { // There is no slave4
187  dataspeed_pds_msgs::Status msg = *master;
188  msg.chan.insert(msg.chan.end(), slave1->chan.begin(), slave1->chan.end());
189  msg.chan.insert(msg.chan.end(), slave2->chan.begin(), slave2->chan.end());
190  msg.chan.insert(msg.chan.end(), slave3->chan.begin(), slave3->chan.end());
191  msg.slave.push_back(slave1->master);
192  msg.slave.push_back(slave2->master);
193  msg.slave.push_back(slave3->master);
194  pub_status_.publish(msg);
195  }
196 }
197 
198 } // namespace dataspeed_pds_lcm
199 
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg > SyncPolicy1
Definition: PdsNode.h:98
message_filters::PassThrough< SyncMsg > sync_msg_master_
Definition: PdsNode.h:104
ros::Subscriber sub_script_
Definition: PdsNode.h:85
void lcmRecvStatus(const lcm::ReceiveBuffer *buf, const std::string &chan, const status_t *lcm)
Definition: PdsNode.cpp:92
const ros::Duration TIMEOUT(0.5)
ros::Publisher pub_status_
Definition: PdsNode.h:88
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
PdsNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh, lcm::LCM *lcm)
Definition: PdsNode.cpp:40
ros::Subscriber sub_mode_
Definition: PdsNode.h:84
message_filters::PassThrough< SyncMsg > sync_msg_slave2_
Definition: PdsNode.h:106
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg, SyncMsg > SyncPolicy3
Definition: PdsNode.h:100
message_filters::PassThrough< SyncMsg > sync_msg_slave3_
Definition: PdsNode.h:107
void recvSyncSlave2(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2)
Definition: PdsNode.cpp:173
void recvSyncSlave3(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2, const SyncPtr &slave3)
Definition: PdsNode.cpp:184
dataspeed_pds_msgs::Status::ConstPtr SyncPtr
Definition: PdsNode.h:97
Connection registerCallback(C &callback)
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg > SyncPolicy2
Definition: PdsNode.h:99
#define ROS_INFO(...)
message_filters::PassThrough< SyncMsg > sync_msg_slave1_
Definition: PdsNode.h:105
message_filters::Synchronizer< SyncPolicy2 > * sync_ros_slave2_
Definition: PdsNode.h:102
ros::Subscriber sub_relay_
Definition: PdsNode.h:83
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void recvSyncSlave1(const SyncPtr &master, const SyncPtr &slave1)
Definition: PdsNode.cpp:164
void recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg)
Definition: PdsNode.cpp:157
message_filters::Synchronizer< SyncPolicy1 > * sync_ros_slave1_
Definition: PdsNode.h:101
void add(const MConstPtr &msg)
static Time now()
void recvMode(const dataspeed_pds_msgs::Mode::ConstPtr &msg)
Definition: PdsNode.cpp:150
message_filters::Synchronizer< SyncPolicy3 > * sync_ros_slave3_
Definition: PdsNode.h:103
void recvRelay(const dataspeed_pds_msgs::Relay::ConstPtr &msg)
Definition: PdsNode.cpp:142


dataspeed_pds_lcm
Author(s): Kevin Hallenbeck , Eric Myllyoja
autogenerated on Sat Jul 11 2020 03:09:53