34 #ifndef RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H 35 #define RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H 60 const std::string& frame_id_prefix)
68 virtual void publishToRos(std::shared_ptr<::google::protobuf::Message> pbMsg);
86 const std::string& frame_id_prefix,
bool tfEnabled)
89 std::string pbMsgType =
_rcdyn->getPbMsgTypeOfStream(
_stream);
90 if (pbMsgType !=
"Frame")
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());
102 virtual void publishToRos(std::shared_ptr<::google::protobuf::Message> pbMsg)
override;
104 std::shared_ptr<tf::TransformBroadcaster>
_tf_pub;
119 const std::string& frame_id_prefix,
bool publishImu2CamAsTf)
120 :
Protobuf2RosStream(rcdIface, stream, nh, frame_id_prefix), _publishVisualizationMarkers(false), _publishImu2CamAsTf(publishImu2CamAsTf)
122 std::string pbMsgType =
_rcdyn->getPbMsgTypeOfStream(
_stream);
123 if (pbMsgType !=
"Dynamics")
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());
135 virtual void publishToRos(std::shared_ptr<::google::protobuf::Message> pbMsg)
override;
139 std::shared_ptr<tf::TransformBroadcaster>
_tf_pub;
144 #endif // RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H std::shared_ptr< Protobuf2RosPublisher > _rosPublisher
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'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
bool _publishVisualizationMarkers
virtual bool checkRosPublishersUsed()
Convenience classes to implement and manage different types of data streams in separate threads...
std::shared_ptr< tf::TransformBroadcaster > _tf_pub
virtual void initRosPublishers()
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