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;
141 };
142 
143 }
144 #endif // RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H
rc::DynamicsStream::_tf_pub
std::shared_ptr< tf::TransformBroadcaster > _tf_pub
Definition: protobuf2ros_stream.h:139
msg
msg
rc::Protobuf2RosStream
Implementation of a ThreadedStream that receives rc_visard's dynamics protobuf messages and re-publis...
Definition: protobuf2ros_stream.h:56
rc::DynamicsStream::_pub_markers
std::shared_ptr< ros::Publisher > _pub_markers
Definition: protobuf2ros_stream.h:138
ros.h
rc::DynamicsStream::publishToRos
virtual void publishToRos(std::shared_ptr<::google::protobuf::Message > pbMsg) override
Definition: protobuf2ros_stream.cc:266
rc::PoseAndTFStream
Specific implementation for roboception::msgs::Frame messages that publishes received messages not on...
Definition: protobuf2ros_stream.h:82
rc::DynamicsStream::_publishImu2CamAsTf
bool _publishImu2CamAsTf
Definition: protobuf2ros_stream.h:140
rc::Protobuf2RosStream::_tfPrefix
const std::string _tfPrefix
Definition: protobuf2ros_stream.h:73
rc::PoseAndTFStream::_tfEnabled
bool _tfEnabled
Definition: protobuf2ros_stream.h:105
rc::DynamicsStream::checkRosPublishersUsed
virtual bool checkRosPublishersUsed() override
Definition: protobuf2ros_stream.cc:261
rc::DynamicsStream::initRosPublishers
virtual void initRosPublishers() override
Definition: protobuf2ros_stream.cc:239
transform_broadcaster.h
rc::dynamics::RemoteInterface::Ptr
std::shared_ptr< RemoteInterface > Ptr
remote_interface.h
ThreadedStream.h
rc::Protobuf2RosStream::startReceivingAndPublishingAsRos
virtual bool startReceivingAndPublishingAsRos() override
Definition: protobuf2ros_stream.cc:53
rc
rc::DynamicsStream
Specific implementation for roboception::msgs::Dynamics messages.
Definition: protobuf2ros_stream.h:115
rc::DynamicsStream::DynamicsStream
DynamicsStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool publishImu2CamAsTf)
Definition: protobuf2ros_stream.h:118
rc::PoseAndTFStream::initRosPublishers
virtual void initRosPublishers() override
Definition: protobuf2ros_stream.cc:209
rc::DynamicsStream::_publishVisualizationMarkers
bool _publishVisualizationMarkers
Definition: protobuf2ros_stream.h:140
rc::Protobuf2RosStream::Protobuf2RosStream
Protobuf2RosStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix)
Definition: protobuf2ros_stream.h:59
rc::Protobuf2RosStream::publishToRos
virtual void publishToRos(std::shared_ptr<::google::protobuf::Message > pbMsg)
Definition: protobuf2ros_stream.cc:204
rc::Protobuf2RosStream::_rosPublisher
std::shared_ptr< Protobuf2RosPublisher > _rosPublisher
Definition: protobuf2ros_stream.h:72
rc::Protobuf2RosStream::initRosPublishers
virtual void initRosPublishers()
Definition: protobuf2ros_stream.cc:193
rc::PoseAndTFStream::_tf_pub
std::shared_ptr< tf::TransformBroadcaster > _tf_pub
Definition: protobuf2ros_stream.h:104
rc::PoseAndTFStream::publishToRos
virtual void publishToRos(std::shared_ptr<::google::protobuf::Message > pbMsg) override
Definition: protobuf2ros_stream.cc:220
rc::Protobuf2RosStream::checkRosPublishersUsed
virtual bool checkRosPublishersUsed()
Definition: protobuf2ros_stream.cc:199
rc::PoseAndTFStream::PoseAndTFStream
PoseAndTFStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool tfEnabled)
Definition: protobuf2ros_stream.h:85
rc::DynamicsStream::_pub_odom
std::shared_ptr< ros::Publisher > _pub_odom
Definition: protobuf2ros_stream.h:137
rc::PoseAndTFStream::checkRosPublishersUsed
virtual bool checkRosPublishersUsed() override
Definition: protobuf2ros_stream.cc:215
rc::ThreadedStream::_rcdyn
rc::dynamics::RemoteInterface::Ptr _rcdyn
Definition: ThreadedStream.h:125
protobuf2ros_publisher.h
rc::ThreadedStream
Convenience classes to implement and manage different types of data streams in separate threads.
Definition: ThreadedStream.h:59
ros::NodeHandle
rc::ThreadedStream::_stream
std::string _stream
Definition: ThreadedStream.h:126


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sun May 15 2022 02:25:43