Go to the documentation of this file.
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;
119 #endif // _PDS_NODE_H_
message_filters::Synchronizer< SyncPolicy3 > * sync_ros_slave3_
message_filters::PassThrough< SyncMsg > sync_msg_slave2_
void recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg)
ros::Publisher pub_status_
ros::Subscriber sub_script_
const ros::Duration TIMEOUT(0.5)
ros::Subscriber sub_mode_
dataspeed_pds_msgs::Status SyncMsg
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg, SyncMsg > SyncPolicy3
message_filters::PassThrough< SyncMsg > sync_msg_slave1_
void recvSyncSlave1(const SyncPtr &master, const SyncPtr &slave1)
ros::Subscriber sub_relay_
message_filters::PassThrough< SyncMsg > sync_msg_slave3_
dataspeed_pds_msgs::Status::ConstPtr SyncPtr
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg > SyncPolicy1
message_filters::Synchronizer< SyncPolicy2 > * sync_ros_slave2_
void recvSyncSlave2(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2)
void recvMode(const dataspeed_pds_msgs::Mode::ConstPtr &msg)
void lcmRecvStatus(const lcm::ReceiveBuffer *buf, const std::string &chan, const status_t *lcm)
void recvSyncSlave3(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2, const SyncPtr &slave3)
void recvRelay(const dataspeed_pds_msgs::Relay::ConstPtr &msg)
PdsNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh, lcm::LCM *lcm)
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg > SyncPolicy2
message_filters::PassThrough< SyncMsg > sync_msg_master_
message_filters::Synchronizer< SyncPolicy1 > * sync_ros_slave1_
dataspeed_pds_lcm
Author(s): Kevin Hallenbeck
, Eric Myllyoja , Michael Lohrer
autogenerated on Wed Mar 2 2022 00:11:47