34 #ifndef RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H 35 #define RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H 55 const std::string& frame_id_prefix)
76 const std::string& frame_id_prefix,
bool tfEnabled)
98 const std::string& frame_id_prefix)
107 #endif // RC_VISARD_ROS_PROTOBUF2ROS_STREAM_H DynamicsStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix)
std::shared_ptr< RemoteInterface > Ptr
Implementation of a ThreadedStream that receives rc_visard's dynamics protobuf messages and re-publis...
Protobuf2RosStream(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix)
Convenience classes to implement and manage different types of data streams in separate threads...
PoseStream(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.
virtual bool startReceivingAndPublishingAsRos() override
const std::string _tfPrefix
Specific implementation for roboception::msgs::Frame messages.