34 #ifndef RC_VISARD_DRIVER_PROTOBUF2ROS_CONVERSIONS_H 35 #define RC_VISARD_DRIVER_PROTOBUF2ROS_CONVERSIONS_H 37 #include <roboception/msgs/imu.pb.h> 38 #include <roboception/msgs/frame.pb.h> 40 #include <geometry_msgs/PoseStamped.h> 41 #include <geometry_msgs/PoseWithCovarianceStamped.h> 42 #include <sensor_msgs/Imu.h> 49 sensor_msgs::ImuPtr
toRosImu(
const roboception::msgs::Imu& imu);
51 geometry_msgs::PosePtr
toRosPose(
const roboception::msgs::Pose& pose);
53 geometry_msgs::PoseStampedPtr
toRosPoseStamped(
const roboception::msgs::Frame& frame);
55 geometry_msgs::PoseStampedPtr
toRosPoseStamped(
const roboception::msgs::Pose& pose,
const roboception::msgs::Time& time,
56 const std::string& frame_id);
65 #endif // RC_VISARD_DRIVER_PROTOBUF2ROS_CONVERSIONS_H geometry_msgs::PoseStampedPtr toRosPoseStamped(const roboception::msgs::Frame &frame)
tf::Transform toRosTfTransform(const roboception::msgs::Pose &pose)
sensor_msgs::ImuPtr toRosImu(const roboception::msgs::Imu &imu)
geometry_msgs::PosePtr toRosPose(const roboception::msgs::Pose &pose)
ros::Time toRosTime(const roboception::msgs::Time &time)
geometry_msgs::PoseWithCovarianceStampedPtr toRosPoseWithCovarianceStamped(const roboception::msgs::Frame &frame)
tf::StampedTransform toRosTfStampedTransform(const roboception::msgs::Frame &frame)