protobuf2ros_stream.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Christian Emmerich
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its contributors
18  * may be used to endorse or promote products derived from this software without
19  * specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H
35 #define RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H
36 
37 #include <memory>
38 
39 #include <ros/ros.h>
41 
43 
44 #include "ThreadedStream.h"
46 
47 namespace rc
48 {
57 {
58 public:
59  Protobuf2RosStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string& stream, ros::NodeHandle& nh,
60  const std::string& frame_id_prefix)
61  : ThreadedStream(rcdIface, stream, nh), _tfPrefix(frame_id_prefix)
62  {
63  }
64 
65 protected:
66  virtual void initRosPublishers();
67  virtual bool checkRosPublishersUsed();
68  virtual void publishToRos(std::shared_ptr<::google::protobuf::Message> pbMsg);
69 
70  virtual bool startReceivingAndPublishingAsRos() override;
71 
72  std::shared_ptr<Protobuf2RosPublisher> _rosPublisher;
73  const std::string _tfPrefix;
74 };
75 
83 {
84 public:
85  PoseAndTFStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string& stream, ros::NodeHandle& nh,
86  const std::string& frame_id_prefix, bool tfEnabled)
87  : Protobuf2RosStream(rcdIface, stream, nh, frame_id_prefix), _tfEnabled(tfEnabled)
88  {
89  std::string pbMsgType = _rcdyn->getPbMsgTypeOfStream(_stream);
90  if (pbMsgType != "Frame")
91  {
92  std::stringstream msg;
93  msg << "Invalid stream type! Can instantiate PoseAndTFStream only for rc_dynamics streams of type 'Frame' "
94  << "but got stream '" << stream << "' which is of type '" << pbMsgType << "'!";
95  throw std::invalid_argument(msg.str());
96  }
97  }
98 
99 protected:
100  virtual void initRosPublishers() override;
101  virtual bool checkRosPublishersUsed() override;
102  virtual void publishToRos(std::shared_ptr<::google::protobuf::Message> pbMsg) override;
103 
104  std::shared_ptr<tf::TransformBroadcaster> _tf_pub;
106 };
107 
116 {
117 public:
118  DynamicsStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string& stream, ros::NodeHandle& nh,
119  const std::string& frame_id_prefix, bool publishImu2CamAsTf)
120  : Protobuf2RosStream(rcdIface, stream, nh, frame_id_prefix), _publishVisualizationMarkers(false), _publishImu2CamAsTf(publishImu2CamAsTf)
121  {
122  std::string pbMsgType = _rcdyn->getPbMsgTypeOfStream(_stream);
123  if (pbMsgType != "Dynamics")
124  {
125  std::stringstream msg;
126  msg << "Invalid stream type! Can instantiate DynamicsStream only for rc_dynamics streams of type 'Dynamics' "
127  << "but got stream '" << stream << "' which is of type '" << pbMsgType << "'!";
128  throw std::invalid_argument(msg.str());
129  }
130  }
131 
132 protected:
133  virtual void initRosPublishers() override;
134  virtual bool checkRosPublishersUsed() override;
135  virtual void publishToRos(std::shared_ptr<::google::protobuf::Message> pbMsg) override;
136 
137  std::shared_ptr<ros::Publisher> _pub_odom;
138  std::shared_ptr<ros::Publisher> _pub_markers;
139  std::shared_ptr<tf::TransformBroadcaster> _tf_pub;
140  bool _publishVisualizationMarkers, _publishImu2CamAsTf;
141 };
142 
143 }
144 #endif // RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H
std::shared_ptr< Protobuf2RosPublisher > _rosPublisher
msg
std::shared_ptr< RemoteInterface > Ptr
std::shared_ptr< ros::Publisher > _pub_markers
Specific implementation for roboception::msgs::Frame messages that publishes received messages not on...
Implementation of a ThreadedStream that receives rc_visard&#39;s dynamics protobuf messages and re-publis...
rc::dynamics::RemoteInterface::Ptr _rcdyn
Protobuf2RosStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix)
std::shared_ptr< tf::TransformBroadcaster > _tf_pub
virtual bool checkRosPublishersUsed()
Convenience classes to implement and manage different types of data streams in separate threads...
std::shared_ptr< tf::TransformBroadcaster > _tf_pub
PoseAndTFStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool tfEnabled)
Specific implementation for roboception::msgs::Dynamics messages.
DynamicsStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool publishImu2CamAsTf)
virtual bool startReceivingAndPublishingAsRos() override
const std::string _tfPrefix
virtual void publishToRos(std::shared_ptr<::google::protobuf::Message > pbMsg)
std::shared_ptr< ros::Publisher > _pub_odom


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sat Feb 13 2021 03:42:55