41 #include <dataspeed_pds_msgs/Mode.h> 42 #include <dataspeed_pds_msgs/Relay.h> 43 #include <dataspeed_pds_msgs/Script.h> 44 #include <dataspeed_pds_msgs/Status.h> 52 #include <lcm/lcm-cpp.hpp> 53 #include <dataspeed_pds_lcm/mode_t.hpp> 54 #include <dataspeed_pds_lcm/relay_request_t.hpp> 55 #include <dataspeed_pds_lcm/script_request_t.hpp> 56 #include <dataspeed_pds_lcm/status_t.hpp> 77 void lcmRecvStatus(
const lcm::ReceiveBuffer* buf,
const std::string &chan,
const status_t *lcm);
78 void recvRelay(
const dataspeed_pds_msgs::Relay::ConstPtr &msg);
79 void recvMode(
const dataspeed_pds_msgs::Mode::ConstPtr &msg);
80 void recvScript(
const dataspeed_pds_msgs::Script::ConstPtr &msg);
96 typedef dataspeed_pds_msgs::Status
SyncMsg;
97 typedef dataspeed_pds_msgs::Status::ConstPtr
SyncPtr;
108 void recvSyncSlave1(
const SyncPtr& master,
const SyncPtr& slave1);
109 void recvSyncSlave2(
const SyncPtr& master,
const SyncPtr& slave1,
const SyncPtr& slave2);
110 void recvSyncSlave3(
const SyncPtr& master,
const SyncPtr& slave1,
const SyncPtr& slave2,
const SyncPtr& slave3);
119 #endif // _PDS_NODE_H_
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_
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
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_
void recvSyncSlave1(const SyncPtr &master, const SyncPtr &slave1)
void recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg)
message_filters::Synchronizer< SyncPolicy1 > * sync_ros_slave1_
dataspeed_pds_msgs::Status SyncMsg
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)