PdsNode.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017-2018, 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 #ifndef _PDS_NODE_H_
36 #define _PDS_NODE_H_
37 
38 #include <ros/ros.h>
39 
40 // ROS messages
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>
45 
46 // Sync messages from multiple units
50 
51 // LCM and messages
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>
57 
58 namespace dataspeed_pds_lcm
59 {
60 
61 typedef enum {
62  MASTER = 0,
63  SLAVE1 = 1,
64  SLAVE2 = 2,
65  SLAVE3 = 3,
66 } UnitId;
67 
68 const ros::Duration TIMEOUT(0.5);
69 
70 class PdsNode
71 {
72 public:
73  PdsNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh, lcm::LCM *lcm);
74  ~PdsNode();
75 
76 private:
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);
81 
82  // Subscribed topics
86 
87  // Published topics
89 
90  // Detect presence of multiple units
94 
95  // Time synchronization of multiple units
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);
111 
112  // LCM object
113  lcm::LCM lcm_;
114 
115 }; // class PdsNode
116 
117 } // namespace dataspeed_pds_lcm
118 
119 #endif // _PDS_NODE_H_
120 
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg > SyncPolicy1
Definition: PdsNode.h:98
message_filters::PassThrough< SyncMsg > sync_msg_master_
Definition: PdsNode.h:104
ros::Subscriber sub_script_
Definition: PdsNode.h:85
void lcmRecvStatus(const lcm::ReceiveBuffer *buf, const std::string &chan, const status_t *lcm)
Definition: PdsNode.cpp:92
const ros::Duration TIMEOUT(0.5)
ros::Publisher pub_status_
Definition: PdsNode.h:88
PdsNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh, lcm::LCM *lcm)
Definition: PdsNode.cpp:40
ros::Subscriber sub_mode_
Definition: PdsNode.h:84
message_filters::PassThrough< SyncMsg > sync_msg_slave2_
Definition: PdsNode.h:106
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg, SyncMsg > SyncPolicy3
Definition: PdsNode.h:100
message_filters::PassThrough< SyncMsg > sync_msg_slave3_
Definition: PdsNode.h:107
void recvSyncSlave2(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2)
Definition: PdsNode.cpp:173
void recvSyncSlave3(const SyncPtr &master, const SyncPtr &slave1, const SyncPtr &slave2, const SyncPtr &slave3)
Definition: PdsNode.cpp:184
dataspeed_pds_msgs::Status::ConstPtr SyncPtr
Definition: PdsNode.h:97
message_filters::sync_policies::ApproximateTime< SyncMsg, SyncMsg, SyncMsg > SyncPolicy2
Definition: PdsNode.h:99
message_filters::PassThrough< SyncMsg > sync_msg_slave1_
Definition: PdsNode.h:105
message_filters::Synchronizer< SyncPolicy2 > * sync_ros_slave2_
Definition: PdsNode.h:102
ros::Subscriber sub_relay_
Definition: PdsNode.h:83
void recvSyncSlave1(const SyncPtr &master, const SyncPtr &slave1)
Definition: PdsNode.cpp:164
void recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg)
Definition: PdsNode.cpp:157
message_filters::Synchronizer< SyncPolicy1 > * sync_ros_slave1_
Definition: PdsNode.h:101
dataspeed_pds_msgs::Status SyncMsg
Definition: PdsNode.h:96
void recvMode(const dataspeed_pds_msgs::Mode::ConstPtr &msg)
Definition: PdsNode.cpp:150
message_filters::Synchronizer< SyncPolicy3 > * sync_ros_slave3_
Definition: PdsNode.h:103
void recvRelay(const dataspeed_pds_msgs::Relay::ConstPtr &msg)
Definition: PdsNode.cpp:142


dataspeed_pds_lcm
Author(s): Kevin Hallenbeck , Eric Myllyoja
autogenerated on Sat Jul 11 2020 03:09:53