MAUVE ROS
Conversion functions
The conversion function used by the Publishers and Subscribers must have the following signature:
template <T,U> bool convert(const T&, U&);
where a data of type T is converted into type U.
When publishing data, T is then the MAUVE type, U the ROS message type.
When subscribing to data, T is the ROS message type, U the MAUVE type.
MAUVE ROS already provides a lot of conversion functions for some common ROS and MAUVE types, within the mauve::ros::conversions
namespace.
Standard types conversions
Available conversion functions between standard C++ types and ROS std_msgs:
convert(const bool&, std_msgs::Bool&)
convert(const std_msgs::Bool&, bool&)
convert(const float&, std_msgs::Float32&)
convert(const std_msgs::Float32&, float&)
convert(const double&, std_msgs::Float32&)
convert(const std_msgs::Float32&, double&)
convert(const double&, std_msgs::Float64&)
convert(const std_msgs::Float64&, double&)
convert(const short&, std_msgs::Int16&)
convert(const std_msgs::Int16&, short&)
convert(const long&, std_msgs::Int32&)
convert(const std_msgs::Int32&, long&)
convert(const long long&, std_msgs::Int64&)
convert(const std_msgs::Int64&, long long&)
convert(const int&, std_msgs::Int16&)
convert(const std_msgs::Int16&, int&)
convert(const int&, std_msgs::Int32&)
convert(const std_msgs::Int32&, int&)
convert(const int&, std_msgs::Int64&)
convert(const std_msgs::Int64&, int&)
convert(const std::string&, std_msgs::String&)
convert(const std_msgs::String&, std::string&)
convert(const unsigned short&, std_msgs::UInt16&)
convert(const std_msgs::UInt16&, unsigned short&)
convert(const unsigned long&, std_msgs::UInt32&)
convert(const std_msgs::UInt32&, unsigned long&)
convert(const unsigned long long&, std_msgs::UInt64&)
convert(const std_msgs::UInt64&, unsigned long long&)
convert(const unsigned int&, std_msgs::UInt16&)
convert(const std_msgs::UInt16&, unsigned int&)
convert(const unsigned int&, std_msgs::UInt32&)
convert(const std_msgs::UInt32&, unsigned int&)
convert(const unsigned int&, std_msgs::UInt64&)
convert(const std_msgs::UInt64&, unsigned int&)
Sensor types conversions
Available conversion functions between MAUVE sensor types and ROS sensor_msgs. When the ROS message has a header, it is not filled by the conversion. You must redefine your own conversion function to fill the header. See the header page.
convert(const sensor_msgs::LaserScan&, mauve::types::sensor::LaserScan&)
convert(const mauve::types::sensor::LaserScan&, sensor_msgs::LaserScan&)
convert(const sensor_msgs::NavSatStatus&, mauve::types::sensor::GNSSStatus&)
convert(const mauve::types::sensor::GNSSStatus&, sensor_msgs::NavSatStatus&)
convert(const sensor_msgs::NavSatFix&, mauve::types::sensor::GNSSStatus&)
convert(const mauve::types::sensor::GNSSStatus&, sensor_msgs::NavSatFix&)
convert(const sensor_msgs::Joy&, mauve::types::sensor::Joy&)
convert(const mauve::types::sensor::Joy&, sensor_msgs::Joy&)
Geometry types conversions
Available conversion functions between MAUVE geometry types and ROS geometry_msgs and nav_msgs. When the ROS message has a header, it is not filled by the conversion. You must redefine your own conversion function to fill the header. See the header page.
convert(const geometry_msgs::Pose2D&, mauve::types::geometry::Pose2D&)
convert(const mauve::types::geometry::Pose2D&, geometry_msgs::Pose2D&)
convert(const geometry_msgs::Pose2D&, mauve::types::geometry::Point2D&)
convert(const mauve::types::geometry::Point2D&, geometry_msgs::Pose2D&)
convert(const geometry_msgs::Point&, mauve::types::geometry::Point2D&)
convert(const mauve::types::geometry::Point2D&, geometry_msgs::Point&)
convert(const geometry_msgs::Pose&, mauve::types::geometry::Pose2D&)
convert(const mauve::types::geometry::Pose2D&, geometry_msgs::Pose&)
convert(const geometry_msgs::PoseWithCovariance&, mauve::types::geometry::Pose2D&)
convert(const mauve::types::geometry::Pose2D&, geometry_msgs::PoseWithCovariance&)
convert(const geometry_msgs::PoseStamped&, mauve::types::geometry::Pose2D&)
convert(const mauve::types::geometry::Pose2D&, geometry_msgs::PoseStamped&)
convert(const geometry_msgs::PoseWithCovarianceStamped&, mauve::types::geometry::Pose2D&)
convert(const mauve::types::geometry::Pose2D&, geometry_msgs::PoseWithCovarianceStamped&)
convert(const mauve::types::geometry::UnicycleVelocity&, geometry_msgs::Twist&)
convert(const geometry_msgs::Twist&, mauve::types::geometry::UnicycleVelocity&)
convert(const nav_msgs::Odometry&, mauve::types::geometry::Pose2D&)
convert(const mauve::types::geometry::Pose2D&, nav_msgs::Odometry&)