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)
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));
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);
66 pub_status_ = node.
advertise<dataspeed_pds_msgs::Status>(
"status", 10);
67 pub_can_ = node.
advertise<can_msgs::Frame>(
"can_tx", 10);
77 if (sync_ros_slave1_) {
78 delete sync_ros_slave1_;
79 sync_ros_slave1_ = NULL;
81 if (sync_ros_slave2_) {
82 delete sync_ros_slave2_;
83 sync_ros_slave2_ = NULL;
85 if (sync_ros_slave3_) {
86 delete sync_ros_slave3_;
87 sync_ros_slave3_ = NULL;
91 void PdsNode::recvCAN(
const can_msgs::Frame::ConstPtr& msg)
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);
134 ROS_WARN(
"Unknown message ID: %1$d (0x%1$01x)", msg->id);
141 void PdsNode::recvRelay(
const dataspeed_pds_msgs::Relay::ConstPtr &msg)
144 ((MsgRelay*)out.data.elems)->channel = msg->channel;
145 ((MsgRelay*)out.data.elems)->request = msg->request;
147 out.dlc =
sizeof(MsgRelay);
148 out.is_extended =
false;
149 pub_can_.publish(out);
152 void PdsNode::recvMode(
const dataspeed_pds_msgs::Mode::ConstPtr &msg)
155 ((MsgMode*)out.data.elems)->mode = msg->mode;
157 out.dlc =
sizeof(MsgMode);
158 out.is_extended =
false;
159 pub_can_.publish(out);
162 void PdsNode::recvScript(
const dataspeed_pds_msgs::Script::ConstPtr &msg)
165 MsgScript *ptr = (MsgScript*)out.data.elems;
166 ((MsgScript*)out.data.elems)->script = msg->script;
168 out.dlc =
sizeof(MsgScript);
169 out.is_extended =
false;
170 pub_can_.publish(out);
173 void PdsNode::recvSync(
const std::vector<can_msgs::Frame::ConstPtr> &msgs,
UnitId id)
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;
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);
227 msg.master.voltage = bytesToVoltage(ptrS2->voltage);
229 msg.master.temp.internal[0] = bytesToCelsius(ptrS2->board_temp);
233 msg.master.temp.internal[1] = msg.master.temp.internal[0];
234 msg.master.temp.internal[2] = msg.master.temp.internal[0];
236 msg.master.temp.internal[1] = NAN;
237 msg.master.temp.internal[2] = NAN;
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;
248 const dataspeed_pds_msgs::Status::ConstPtr ptr(
new dataspeed_pds_msgs::Status(msg));
252 sync_msg_master_.add(ptr);
253 if ((now - stamp_slave1_) >
TIMEOUT) {
254 pub_status_.publish(msg);
259 sync_msg_slave1_.add(ptr);
263 sync_msg_slave2_.add(ptr);
267 sync_msg_slave3_.add(ptr);
273 void PdsNode::recvSyncSlave1(
const SyncPtr& master,
const SyncPtr& slave1)
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);
282 void PdsNode::recvSyncSlave2(
const SyncPtr& master,
const SyncPtr& slave1,
const SyncPtr& slave2)
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);
293 void PdsNode::recvSyncSlave3(
const SyncPtr& master,
const SyncPtr& slave1,
const SyncPtr& slave2,
const SyncPtr& slave3)
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);