PdsNode.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017-2018, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #ifndef _PDS_NODE_H_
00036 #define _PDS_NODE_H_
00037 
00038 #include <ros/ros.h>
00039 
00040 // ROS messages
00041 #include <dataspeed_pds_msgs/Mode.h>
00042 #include <dataspeed_pds_msgs/Relay.h>
00043 #include <dataspeed_pds_msgs/Script.h>
00044 #include <dataspeed_pds_msgs/Status.h>
00045 
00046 // Sync messages from multiple units
00047 #include <message_filters/pass_through.h>
00048 #include <message_filters/synchronizer.h>
00049 #include <message_filters/sync_policies/approximate_time.h>
00050 
00051 // LCM and messages
00052 #include <lcm/lcm-cpp.hpp>
00053 #include <dataspeed_pds_lcm/mode_t.hpp>
00054 #include <dataspeed_pds_lcm/relay_request_t.hpp>
00055 #include <dataspeed_pds_lcm/script_request_t.hpp>
00056 #include <dataspeed_pds_lcm/status_t.hpp>
00057 
00058 namespace dataspeed_pds_lcm
00059 {
00060 
00061 typedef enum {
00062   MASTER = 0,
00063   SLAVE1 = 1,
00064   SLAVE2 = 2,
00065   SLAVE3 = 3,
00066 } UnitId;
00067 
00068 const ros::Duration TIMEOUT(0.5);
00069 
00070 class PdsNode
00071 {
00072 public:
00073   PdsNode(ros::NodeHandle &node, ros::NodeHandle &priv_nh, lcm::LCM *lcm);
00074   ~PdsNode();
00075 
00076 private:
00077   void lcmRecvStatus(const lcm::ReceiveBuffer* buf, const std::string &chan, const status_t *lcm);
00078   void recvRelay(const dataspeed_pds_msgs::Relay::ConstPtr &msg);
00079   void recvMode(const dataspeed_pds_msgs::Mode::ConstPtr &msg);
00080   void recvScript(const dataspeed_pds_msgs::Script::ConstPtr &msg);
00081 
00082   // Subscribed topics
00083   ros::Subscriber sub_relay_;
00084   ros::Subscriber sub_mode_;
00085   ros::Subscriber sub_script_;
00086 
00087   // Published topics
00088   ros::Publisher pub_status_;
00089 
00090   // Detect presence of multiple units
00091   ros::Time stamp_slave1_;
00092   ros::Time stamp_slave2_;
00093   ros::Time stamp_slave3_;
00094 
00095   // Time synchronization of multiple units
00096   typedef dataspeed_pds_msgs::Status SyncMsg;
00097   typedef dataspeed_pds_msgs::Status::ConstPtr SyncPtr;
00098   typedef message_filters::sync_policies::ApproximateTime<SyncMsg, SyncMsg> SyncPolicy1;
00099   typedef message_filters::sync_policies::ApproximateTime<SyncMsg, SyncMsg, SyncMsg> SyncPolicy2;
00100   typedef message_filters::sync_policies::ApproximateTime<SyncMsg, SyncMsg, SyncMsg, SyncMsg> SyncPolicy3;
00101   message_filters::Synchronizer<SyncPolicy1> *sync_ros_slave1_;
00102   message_filters::Synchronizer<SyncPolicy2> *sync_ros_slave2_;
00103   message_filters::Synchronizer<SyncPolicy3> *sync_ros_slave3_;
00104   message_filters::PassThrough<SyncMsg> sync_msg_master_;
00105   message_filters::PassThrough<SyncMsg> sync_msg_slave1_;
00106   message_filters::PassThrough<SyncMsg> sync_msg_slave2_;
00107   message_filters::PassThrough<SyncMsg> sync_msg_slave3_;
00108   void recvSyncSlave1(const SyncPtr& master, const SyncPtr& slave1);
00109   void recvSyncSlave2(const SyncPtr& master, const SyncPtr& slave1, const SyncPtr& slave2);
00110   void recvSyncSlave3(const SyncPtr& master, const SyncPtr& slave1, const SyncPtr& slave2, const SyncPtr& slave3);
00111 
00112   // LCM object
00113   lcm::LCM lcm_;
00114 
00115 }; // class PdsNode
00116 
00117 } // namespace dataspeed_pds_lcm
00118 
00119 #endif // _PDS_NODE_H_
00120 


dataspeed_pds_lcm
Author(s): Kevin Hallenbeck , Eric Myllyoja
autogenerated on Thu Apr 4 2019 02:42:50