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);
94 ROS_INFO(
"Received LCM message from channel '%s'", chan.c_str());
101 dataspeed_pds_msgs::Status msg;
102 msg.header.stamp = now;
103 msg.mode.mode = lcm->mode;
104 msg.script.script = 0;
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];
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;
119 const dataspeed_pds_msgs::Status::ConstPtr ptr(
new dataspeed_pds_msgs::Status(msg));
120 switch (lcm->unit_id) {
145 out.channel = msg->channel;
146 out.request = msg->request;
147 lcm_.publish(
"RELAY", &out);
153 out.mode = msg->mode;
154 lcm_.publish(
"MODE", &out);
159 script_request_t out;
160 out.script = msg->script;
161 lcm_.publish(
"SCRIPT", &out);
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);
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);
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);
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg > SyncPolicy1
message_filters::PassThrough< SyncMsg > sync_msg_master_
ros::Subscriber sub_script_
void lcmRecvStatus(const lcm::ReceiveBuffer *buf, const std::string &chan, const status_t *lcm)
const ros::Duration TIMEOUT(0.5)
ros::Publisher pub_status_
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)
ros::Subscriber sub_mode_
message_filters::PassThrough< SyncMsg > sync_msg_slave2_
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg, SyncMsg > SyncPolicy3
message_filters::PassThrough< SyncMsg > sync_msg_slave3_
void recvSyncSlave2(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2)
void recvSyncSlave3(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2, const SyncPtr &slave3)
dataspeed_pds_msgs::Status::ConstPtr SyncPtr
Connection registerCallback(C &callback)
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg > SyncPolicy2
message_filters::PassThrough< SyncMsg > sync_msg_slave1_
message_filters::Synchronizer< SyncPolicy2 > * sync_ros_slave2_
ros::Subscriber sub_relay_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void recvSyncSlave1(const SyncPtr &master, const SyncPtr &slave1)
void recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg)
message_filters::Synchronizer< SyncPolicy1 > * sync_ros_slave1_
void add(const MConstPtr &msg)
void recvMode(const dataspeed_pds_msgs::Mode::ConstPtr &msg)
message_filters::Synchronizer< SyncPolicy3 > * sync_ros_slave3_
void recvRelay(const dataspeed_pds_msgs::Relay::ConstPtr &msg)