PdsNode.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017-2020, 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"
37 
38 namespace dataspeed_pds_can
39 {
40 
42 : sync_can_master_(8, boost::bind(&PdsNode::recvSync, this, _1, MASTER), ID_STATUS1_MASTER, ID_STATUS2_MASTER, ID_CURRENT1_MASTER, ID_CURRENT2_MASTER, ID_CURRENT3_MASTER)
43 , sync_can_slave1_(8, boost::bind(&PdsNode::recvSync, this, _1, SLAVE1), ID_STATUS1_SLAVE1, ID_STATUS2_SLAVE1, ID_CURRENT1_SLAVE1, ID_CURRENT2_SLAVE1, ID_CURRENT3_SLAVE1)
44 , sync_can_slave2_(8, boost::bind(&PdsNode::recvSync, this, _1, SLAVE2), ID_STATUS1_SLAVE2, ID_STATUS2_SLAVE2, ID_CURRENT1_SLAVE2, ID_CURRENT2_SLAVE2, ID_CURRENT3_SLAVE2)
45 , sync_can_slave3_(8, boost::bind(&PdsNode::recvSync, this, _1, SLAVE3), ID_STATUS1_SLAVE3, ID_STATUS2_SLAVE3, ID_CURRENT1_SLAVE3, ID_CURRENT2_SLAVE3, ID_CURRENT3_SLAVE3)
46 {
47  // Setup message synchronizers
48  sync_ros_slave1_ = new message_filters::Synchronizer<SyncPolicy1>(SyncPolicy1(4), sync_msg_master_, sync_msg_slave1_);
49  sync_ros_slave2_ = new message_filters::Synchronizer<SyncPolicy2>(SyncPolicy2(4), sync_msg_master_, sync_msg_slave1_, sync_msg_slave2_);
50  sync_ros_slave3_ = new message_filters::Synchronizer<SyncPolicy3>(SyncPolicy3(4), sync_msg_master_, sync_msg_slave1_, sync_msg_slave2_, sync_msg_slave3_);
51  sync_ros_slave1_->registerCallback(boost::bind(&PdsNode::recvSyncSlave1, this, _1, _2));
52  sync_ros_slave2_->registerCallback(boost::bind(&PdsNode::recvSyncSlave2, this, _1, _2, _3));
53  sync_ros_slave3_->registerCallback(boost::bind(&PdsNode::recvSyncSlave3, this, _1, _2, _3, _4));
54 
55  // Reduce synchronization delay
56  const ros::Duration SYNC_50_MS(0.016); // 30% of 50ms period
57  sync_can_master_.setInterMessageLowerBound(SYNC_50_MS);
58  sync_can_slave1_.setInterMessageLowerBound(SYNC_50_MS);
59  sync_can_slave2_.setInterMessageLowerBound(SYNC_50_MS);
60  sync_can_slave3_.setInterMessageLowerBound(SYNC_50_MS);
61  sync_ros_slave1_->setInterMessageLowerBound(SYNC_50_MS);
62  sync_ros_slave2_->setInterMessageLowerBound(SYNC_50_MS);
63  sync_ros_slave3_->setInterMessageLowerBound(SYNC_50_MS);
64 
65  // Setup Publishers
66  pub_status_ = node.advertise<dataspeed_pds_msgs::Status>("status", 10);
67  pub_can_ = node.advertise<can_msgs::Frame>("can_tx", 10);
68 
69  // Setup Subscribers
70  sub_relay_ = node.subscribe("relay", 10, &PdsNode::recvRelay, this, ros::TransportHints().tcpNoDelay(true));
71  sub_mode_ = node.subscribe("mode", 10, &PdsNode::recvMode, this, ros::TransportHints().tcpNoDelay(true));
72  sub_script_ = node.subscribe("script", 10, &PdsNode::recvScript, this, ros::TransportHints().tcpNoDelay(true));
73  sub_can_ = node.subscribe("can_rx", 80, &PdsNode::recvCAN, this, ros::TransportHints().tcpNoDelay(true));
74 }
75 PdsNode::~PdsNode()
76 {
77  if (sync_ros_slave1_) {
78  delete sync_ros_slave1_;
79  sync_ros_slave1_ = NULL;
80  }
81  if (sync_ros_slave2_) {
82  delete sync_ros_slave2_;
83  sync_ros_slave2_ = NULL;
84  }
85  if (sync_ros_slave3_) {
86  delete sync_ros_slave3_;
87  sync_ros_slave3_ = NULL;
88  }
89 }
90 
91 void PdsNode::recvCAN(const can_msgs::Frame::ConstPtr& msg)
92 {
93  if (!msg->is_rtr && !msg->is_error && !msg->is_extended) {
94  sync_can_master_.processMsg(msg);
95  sync_can_slave1_.processMsg(msg);
96  sync_can_slave2_.processMsg(msg);
97  sync_can_slave3_.processMsg(msg);
98  switch (msg->id) {
99  case ID_REQUEST: // These command messages aren't handled.
100  case ID_MODE:
101  case ID_SCRIPT:
102  break;
103  case ID_RESERVED1: // Reserved for the Touchscreen Display
104  case ID_RESERVED2:
105  case ID_RESERVED3:
106  case ID_RESERVED4:
107  break;
108  case ID_STATUS1_MASTER:
109  case ID_STATUS2_MASTER:
110  case ID_CURRENT1_MASTER:
111  case ID_CURRENT2_MASTER:
112  case ID_CURRENT3_MASTER:
113  break;
114  case ID_STATUS1_SLAVE1:
115  case ID_STATUS2_SLAVE1:
116  case ID_CURRENT1_SLAVE1:
117  case ID_CURRENT2_SLAVE1:
118  case ID_CURRENT3_SLAVE1:
119  break;
120  case ID_STATUS1_SLAVE2:
121  case ID_STATUS2_SLAVE2:
122  case ID_CURRENT1_SLAVE2:
124  case ID_CURRENT3_SLAVE2:
125  break;
126  case ID_STATUS1_SLAVE3:
127  case ID_STATUS2_SLAVE3:
128  case ID_CURRENT1_SLAVE3:
129  case ID_CURRENT2_SLAVE3:
130  case ID_CURRENT3_SLAVE3:
131  break;
132  default:
133 #if 0
134  ROS_WARN("Unknown message ID: %1$d (0x%1$01x)", msg->id);
135 #endif
136  break;
137  }
138  }
139 }
140 
141 void PdsNode::recvRelay(const dataspeed_pds_msgs::Relay::ConstPtr &msg)
142 {
143  can_msgs::Frame out;
144  ((MsgRelay*)out.data.elems)->channel = msg->channel;
145  ((MsgRelay*)out.data.elems)->request = msg->request;
146  out.id = ID_REQUEST;
147  out.dlc = sizeof(MsgRelay);
148  out.is_extended = false;
149  pub_can_.publish(out);
150 }
151 
152 void PdsNode::recvMode(const dataspeed_pds_msgs::Mode::ConstPtr &msg)
153 {
154  can_msgs::Frame out;
155  ((MsgMode*)out.data.elems)->mode = msg->mode;
156  out.id = ID_MODE;
157  out.dlc = sizeof(MsgMode);
158  out.is_extended = false;
159  pub_can_.publish(out);
160 }
161 
162 void PdsNode::recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg)
163 {
164  can_msgs::Frame out;
165  MsgScript *ptr = (MsgScript*)out.data.elems;
166  ((MsgScript*)out.data.elems)->script = msg->script;
167  out.id = ID_SCRIPT;
168  out.dlc = sizeof(MsgScript);
169  out.is_extended = false;
170  pub_can_.publish(out);
171 }
172 
173 void PdsNode::recvSync(const std::vector<can_msgs::Frame::ConstPtr> &msgs, UnitId id)
174 {
175  ROS_ASSERT((MASTER <= id) && (id <= SLAVE3));
176  ROS_ASSERT(msgs.size() == 5);
177  ROS_ASSERT(msgs[0]->id == ID_STATUS1_MASTER + id);
178  ROS_ASSERT(msgs[1]->id == ID_STATUS2_MASTER + id);
179  ROS_ASSERT(msgs[2]->id == ID_CURRENT1_MASTER + id);
180  ROS_ASSERT(msgs[3]->id == ID_CURRENT2_MASTER + id);
181  ROS_ASSERT(msgs[4]->id == ID_CURRENT3_MASTER + id);
182  if ((msgs[0]->dlc >= sizeof(MsgStatus1))
183  && (msgs[1]->dlc >= sizeof(MsgStatus2))
184  && (msgs[2]->dlc >= sizeof(MsgCurrent))
185  && (msgs[3]->dlc >= sizeof(MsgCurrent))
186  && (msgs[4]->dlc >= sizeof(MsgCurrent))) {
187  const MsgStatus1 *ptrS1 = (const MsgStatus1*)msgs[0]->data.elems;
188  const MsgStatus2 *ptrS2 = (const MsgStatus2*)msgs[1]->data.elems;
189  const MsgCurrent *ptrC1 = (const MsgCurrent*)msgs[2]->data.elems;
190  const MsgCurrent *ptrC2 = (const MsgCurrent*)msgs[3]->data.elems;
191  const MsgCurrent *ptrC3 = (const MsgCurrent*)msgs[4]->data.elems;
192 
193  // Merge CAN messages into a single ROS message
194  dataspeed_pds_msgs::Status msg;
195  msg.header.stamp = msgs[0]->header.stamp;
196  msg.mode.mode = ptrS1->mode;
197  msg.script.script = ptrS1->script;
198  msg.chan.resize(12);
199  msg.chan[ 0].status = ptrS1->status_01;
200  msg.chan[ 1].status = ptrS1->status_02;
201  msg.chan[ 2].status = ptrS1->status_03;
202  msg.chan[ 3].status = ptrS1->status_04;
203  msg.chan[ 4].status = ptrS1->status_05;
204  msg.chan[ 5].status = ptrS1->status_06;
205  msg.chan[ 6].status = ptrS1->status_07;
206  msg.chan[ 7].status = ptrS1->status_08;
207  msg.chan[ 8].status = ptrS1->status_09;
208  msg.chan[ 9].status = ptrS1->status_10;
209  msg.chan[10].status = ptrS1->status_11;
210  msg.chan[11].status = ptrS1->status_12;
211  msg.chan[ 0].current = bytesToAmperes(ptrC1->current_01);
212  msg.chan[ 1].current = bytesToAmperes(ptrC1->current_02);
213  msg.chan[ 2].current = bytesToAmperes(ptrC1->current_03);
214  msg.chan[ 3].current = bytesToAmperes(ptrC1->current_04);
215  msg.chan[ 4].current = bytesToAmperes(ptrC2->current_05);
216  msg.chan[ 5].current = bytesToAmperes(ptrC2->current_06);
217  msg.chan[ 6].current = bytesToAmperes(ptrC2->current_07);
218  msg.chan[ 7].current = bytesToAmperes(ptrC2->current_08);
219  msg.chan[ 8].current = bytesToAmperes(ptrC3->current_09);
220  msg.chan[ 9].current = bytesToAmperes(ptrC3->current_10);
221  msg.chan[10].current = bytesToAmperes(ptrC3->current_11);
222  msg.chan[11].current = bytesToAmperes(ptrC3->current_12);
223  msg.master.inverter.request = ptrS1->inverter_request;
224  msg.master.inverter.status = ptrS1->inverter_status;
225  msg.master.inverter.overload = ptrS1->inverter_overload;
226  msg.master.inverter.overtemp = ptrS1->inverter_overtemp;
227  msg.master.voltage = bytesToVoltage(ptrS2->voltage);
228 
229  msg.master.temp.internal[0] = bytesToCelsius(ptrS2->board_temp);
230  if (ptrS1->rev >= REV_H) {
231  // In hardware >=RevH, three internal temperature sensors are present.
232  // However, CAN only reports the max of all three temps
233  msg.master.temp.internal[1] = msg.master.temp.internal[0];
234  msg.master.temp.internal[2] = msg.master.temp.internal[0];
235  } else {
236  msg.master.temp.internal[1] = NAN;
237  msg.master.temp.internal[2] = NAN;
238  }
239 
240  // For now only 1 external temp sensor is supported.
241  // In the future 4 will be supported.
242  msg.master.temp.external[0] = bytesToCelsius(ptrS2->thermocouple_temp);
243  msg.master.temp.external[1] = NAN;
244  msg.master.temp.external[2] = NAN;
245  msg.master.temp.external[3] = NAN;
246 
247  // Publish for single unit, or forward to multi-unit synchronization
248  const dataspeed_pds_msgs::Status::ConstPtr ptr(new dataspeed_pds_msgs::Status(msg));
249  const ros::Time now = ros::Time::now();
250  switch (id) {
251  case MASTER:
252  sync_msg_master_.add(ptr);
253  if ((now - stamp_slave1_) > TIMEOUT) {
254  pub_status_.publish(msg);
255  }
256  break;
257  case SLAVE1:
258  stamp_slave1_ = now;
259  sync_msg_slave1_.add(ptr);
260  break;
261  case SLAVE2:
262  stamp_slave2_ = now;
263  sync_msg_slave2_.add(ptr);
264  break;
265  case SLAVE3:
266  stamp_slave3_ = now;
267  sync_msg_slave3_.add(ptr);
268  break;
269  }
270  }
271 }
272 
273 void PdsNode::recvSyncSlave1(const SyncPtr& master, const SyncPtr& slave1)
274 {
275  if ((ros::Time::now() - stamp_slave2_) > TIMEOUT) {
276  dataspeed_pds_msgs::Status msg = *master;
277  msg.chan.insert(msg.chan.end(), slave1->chan.begin(), slave1->chan.end());
278  msg.slave.push_back(slave1->master);
279  pub_status_.publish(msg);
280  }
281 }
282 void PdsNode::recvSyncSlave2(const SyncPtr& master, const SyncPtr& slave1, const SyncPtr& slave2)
283 {
284  if ((ros::Time::now() - stamp_slave3_) > TIMEOUT) {
285  dataspeed_pds_msgs::Status msg = *master;
286  msg.chan.insert(msg.chan.end(), slave1->chan.begin(), slave1->chan.end());
287  msg.chan.insert(msg.chan.end(), slave2->chan.begin(), slave2->chan.end());
288  msg.slave.push_back(slave1->master);
289  msg.slave.push_back(slave2->master);
290  pub_status_.publish(msg);
291  }
292 }
293 void PdsNode::recvSyncSlave3(const SyncPtr& master, const SyncPtr& slave1, const SyncPtr& slave2, const SyncPtr& slave3)
294 {
295  if (1) { // There is no slave4
296  dataspeed_pds_msgs::Status msg = *master;
297  msg.chan.insert(msg.chan.end(), slave1->chan.begin(), slave1->chan.end());
298  msg.chan.insert(msg.chan.end(), slave2->chan.begin(), slave2->chan.end());
299  msg.chan.insert(msg.chan.end(), slave3->chan.begin(), slave3->chan.end());
300  msg.slave.push_back(slave1->master);
301  msg.slave.push_back(slave2->master);
302  msg.slave.push_back(slave3->master);
303  pub_status_.publish(msg);
304  }
305 }
306 
307 } // namespace dataspeed_pds_can
308 
dataspeed_pds_can::ID_CURRENT1_SLAVE2
@ ID_CURRENT1_SLAVE2
Definition: dispatch.h:171
dataspeed_pds_can::ID_CURRENT2_SLAVE2
@ ID_CURRENT2_SLAVE2
Definition: dispatch.h:175
dataspeed_pds_can::ID_STATUS1_SLAVE2
@ ID_STATUS1_SLAVE2
Definition: dispatch.h:167
dataspeed_pds_can::MsgStatus1::script
uint8_t script
Definition: dispatch.h:98
dataspeed_pds_can::ID_CURRENT2_SLAVE3
@ ID_CURRENT2_SLAVE3
Definition: dispatch.h:176
dataspeed_pds_can::ID_CURRENT3_SLAVE1
@ ID_CURRENT3_SLAVE1
Definition: dispatch.h:178
PdsNode.h
dataspeed_pds_can::MsgStatus1
Definition: dispatch.h:81
message_filters::Synchronizer
dataspeed_pds_can::ID_RESERVED3
@ ID_RESERVED3
Definition: dispatch.h:163
dataspeed_pds_can::SLAVE3
@ SLAVE3
Definition: PdsNode.h:124
dataspeed_pds_can::ID_CURRENT1_SLAVE3
@ ID_CURRENT1_SLAVE3
Definition: dispatch.h:172
dataspeed_pds_can::ID_CURRENT2_SLAVE1
@ ID_CURRENT2_SLAVE1
Definition: dispatch.h:174
dataspeed_pds_can::ID_STATUS2_SLAVE2
@ ID_STATUS2_SLAVE2
Definition: dispatch.h:183
dataspeed_pds_can::MsgStatus1::status_10
uint8_t status_10
Definition: dispatch.h:106
dataspeed_pds_can::MsgStatus1::inverter_overtemp
uint8_t inverter_overtemp
Definition: dispatch.h:92
dataspeed_pds_can::SLAVE1
@ SLAVE1
Definition: PdsNode.h:122
dataspeed_pds_can::MsgStatus1::inverter_request
uint8_t inverter_request
Definition: dispatch.h:86
ros::TransportHints
dataspeed_pds_can::ID_CURRENT3_MASTER
@ ID_CURRENT3_MASTER
Definition: dispatch.h:177
boost
dataspeed_pds_can::MsgStatus1::status_02
uint8_t status_02
Definition: dispatch.h:102
dataspeed_pds_can::ID_CURRENT1_MASTER
@ ID_CURRENT1_MASTER
Definition: dispatch.h:169
dataspeed_pds_can::ID_STATUS2_SLAVE1
@ ID_STATUS2_SLAVE1
Definition: dispatch.h:182
dataspeed_pds_can::MsgStatus1::status_06
uint8_t status_06
Definition: dispatch.h:104
dataspeed_pds_can::ID_STATUS1_SLAVE1
@ ID_STATUS1_SLAVE1
Definition: dispatch.h:166
dataspeed_pds_can::MsgStatus2
Definition: dispatch.h:110
dataspeed_pds_can::ID_STATUS1_SLAVE3
@ ID_STATUS1_SLAVE3
Definition: dispatch.h:168
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
dataspeed_pds_can::ID_CURRENT3_SLAVE2
@ ID_CURRENT3_SLAVE2
Definition: dispatch.h:179
dataspeed_pds_can::TIMEOUT
const ros::Duration TIMEOUT(0.5)
dataspeed_pds_can::MsgStatus1::status_08
uint8_t status_08
Definition: dispatch.h:105
dispatch.h
dataspeed_pds_can::ID_SCRIPT
@ ID_SCRIPT
Definition: dispatch.h:160
dataspeed_pds_can::MsgCurrent::current_12
int16_t current_12
Definition: dispatch.h:130
dataspeed_pds_can::MsgCurrent::current_04
int16_t current_04
Definition: dispatch.h:130
dataspeed_pds_can::MsgCurrent
Definition: dispatch.h:125
dataspeed_pds_can::MsgCurrent::current_09
int16_t current_09
Definition: dispatch.h:127
dataspeed_pds_can::MsgStatus1::status_07
uint8_t status_07
Definition: dispatch.h:105
dataspeed_pds_can::MsgStatus1::status_01
uint8_t status_01
Definition: dispatch.h:102
dataspeed_pds_can::ID_MODE
@ ID_MODE
Definition: dispatch.h:159
dataspeed_pds_can
Definition: dispatch.h:39
dataspeed_pds_can::ID_CURRENT2_MASTER
@ ID_CURRENT2_MASTER
Definition: dispatch.h:173
dataspeed_pds_can::MsgStatus1::status_09
uint8_t status_09
Definition: dispatch.h:106
dataspeed_pds_can::ID_RESERVED1
@ ID_RESERVED1
Definition: dispatch.h:161
dataspeed_pds_can::MsgStatus1::status_05
uint8_t status_05
Definition: dispatch.h:104
dataspeed_pds_can::MsgCurrent::current_01
int16_t current_01
Definition: dispatch.h:127
ROS_WARN
#define ROS_WARN(...)
dataspeed_pds_can::MsgCurrent::current_03
int16_t current_03
Definition: dispatch.h:129
dataspeed_pds_can::MsgCurrent::current_11
int16_t current_11
Definition: dispatch.h:129
dataspeed_pds_can::ID_CURRENT1_SLAVE1
@ ID_CURRENT1_SLAVE1
Definition: dispatch.h:170
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
dataspeed_pds_can::ID_STATUS2_MASTER
@ ID_STATUS2_MASTER
Definition: dispatch.h:181
dataspeed_pds_can::ID_RESERVED4
@ ID_RESERVED4
Definition: dispatch.h:164
dataspeed_pds_can::ID_RESERVED2
@ ID_RESERVED2
Definition: dispatch.h:162
dataspeed_pds_can::REV_H
@ REV_H
Definition: dispatch.h:110
ros::Time
dataspeed_pds_can::ID_STATUS1_MASTER
@ ID_STATUS1_MASTER
Definition: dispatch.h:165
dataspeed_pds_can::MsgStatus1::status_11
uint8_t status_11
Definition: dispatch.h:107
dataspeed_pds_can::MsgCurrent::current_10
int16_t current_10
Definition: dispatch.h:128
dataspeed_pds_can::ID_STATUS2_SLAVE3
@ ID_STATUS2_SLAVE3
Definition: dispatch.h:184
dataspeed_pds_can::MsgStatus1::status_03
uint8_t status_03
Definition: dispatch.h:103
dataspeed_pds_can::SLAVE2
@ SLAVE2
Definition: PdsNode.h:123
dataspeed_pds_can::MASTER
@ MASTER
Definition: PdsNode.h:121
dataspeed_pds_can::MsgStatus1::mode
uint8_t mode
Definition: dispatch.h:95
dataspeed_pds_can::MsgStatus1::status_12
uint8_t status_12
Definition: dispatch.h:107
dataspeed_pds_can::UnitId
UnitId
Definition: PdsNode.h:88
dataspeed_pds_can::ID_CURRENT3_SLAVE3
@ ID_CURRENT3_SLAVE3
Definition: dispatch.h:180
dataspeed_pds_can::MsgStatus1::inverter_status
uint8_t inverter_status
Definition: dispatch.h:88
dataspeed_pds_can::MsgCurrent::current_02
int16_t current_02
Definition: dispatch.h:128
ROS_ASSERT
#define ROS_ASSERT(cond)
dataspeed_pds_can::PdsNode::PdsNode
PdsNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
Definition: PdsNode.cpp:73
ros::Duration
dataspeed_pds_can::MsgStatus1::status_04
uint8_t status_04
Definition: dispatch.h:103
dataspeed_pds_can::ID_REQUEST
@ ID_REQUEST
Definition: dispatch.h:158
ros::NodeHandle
dataspeed_pds_can::MsgStatus1::inverter_overload
uint8_t inverter_overload
Definition: dispatch.h:90
ros::Time::now
static Time now()
dataspeed_pds_can::MsgStatus1::rev
uint8_t rev
Definition: dispatch.h:84


dataspeed_pds_can
Author(s): Kevin Hallenbeck , Eric Myllyoja , Michael Lohrer
autogenerated on Wed Mar 2 2022 00:11:44