6#ifndef MRS_LIB_MSG_EXTRACTOR_H
7#define MRS_LIB_MSG_EXTRACTOR_H
9#include <mrs_msgs/msg/reference.hpp>
10#include <mrs_msgs/msg/reference_stamped.hpp>
11#include <mrs_msgs/msg/tracker_command.hpp>
13#include <nav_msgs/msg/odometry.hpp>
29 std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Point& data);
38 std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Point::SharedPtr& data);
47 std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Point::ConstSharedPtr& data);
60 std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Vector3& data);
69 std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Vector3::SharedPtr& data);
78 std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Vector3::ConstSharedPtr& data);
93 std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::Pose& data);
102 std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::Pose::SharedPtr& data);
111 std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::Pose::ConstSharedPtr& data);
124 double getHeading(
const geometry_msgs::msg::Pose& data);
133 double getHeading(
const geometry_msgs::msg::Pose::SharedPtr& data);
142 double getHeading(
const geometry_msgs::msg::Pose::ConstSharedPtr& data);
155 double getYaw(
const geometry_msgs::msg::Pose& data);
164 double getYaw(
const geometry_msgs::msg::Pose::SharedPtr& data);
173 double getYaw(
const geometry_msgs::msg::Pose::ConstSharedPtr& data);
190 std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::PoseWithCovariance& data);
199 std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
208 std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
221 double getHeading(
const geometry_msgs::msg::PoseWithCovariance& data);
230 double getHeading(
const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
239 double getHeading(
const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
252 double getYaw(
const geometry_msgs::msg::PoseWithCovariance& data);
261 double getYaw(
const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
270 double getYaw(
const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
287 std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::Twist& data);
296 std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::Twist::SharedPtr& data);
305 std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::Twist::ConstSharedPtr& data);
322 std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::TwistWithCovariance& data);
331 std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::TwistWithCovariance::SharedPtr& data);
340 std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::TwistWithCovariance::ConstSharedPtr& data);
357 std::tuple<double, double, double>
getPosition(
const nav_msgs::msg::Odometry& data);
366 std::tuple<double, double, double>
getPosition(
const nav_msgs::msg::Odometry::SharedPtr& data);
375 std::tuple<double, double, double>
getPosition(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
388 std::tuple<double, double, double>
getVelocity(
const nav_msgs::msg::Odometry& data);
397 std::tuple<double, double, double>
getVelocity(
const nav_msgs::msg::Odometry::SharedPtr& data);
406 std::tuple<double, double, double>
getVelocity(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
420 double getHeading(
const nav_msgs::msg::Odometry& data);
429 double getHeading(
const nav_msgs::msg::Odometry::SharedPtr& data);
438 double getHeading(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
451 double getHeading(
const nav_msgs::msg::Odometry& data);
460 double getHeading(
const nav_msgs::msg::Odometry::SharedPtr& data);
469 double getHeading(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
482 double getYaw(
const nav_msgs::msg::Odometry& data);
491 double getYaw(
const nav_msgs::msg::Odometry::SharedPtr& data);
500 double getYaw(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
513 geometry_msgs::msg::Pose
getPose(
const nav_msgs::msg::Odometry& data);
522 geometry_msgs::msg::Pose
getPose(
const nav_msgs::msg::Odometry::SharedPtr& data);
531 geometry_msgs::msg::Pose
getPose(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
548 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::TrackerCommand& data);
557 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
566 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
580 std::tuple<double, double, double>
getVelocity(
const mrs_msgs::msg::TrackerCommand& data);
589 std::tuple<double, double, double>
getVelocity(
const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
598 std::tuple<double, double, double>
getVelocity(
const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
612 double getHeading(
const mrs_msgs::msg::TrackerCommand& data);
621 double getHeading(
const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
630 double getHeading(
const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
647 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::Reference& data);
656 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::Reference::SharedPtr& data);
665 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::Reference::ConstSharedPtr& data);
678 double getHeading(
const mrs_msgs::msg::Reference& data);
687 double getHeading(
const mrs_msgs::msg::Reference::SharedPtr& data);
696 double getHeading(
const mrs_msgs::msg::Reference::ConstSharedPtr& data);
713 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::ReferenceStamped& data);
722 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::ReferenceStamped::SharedPtr& data);
731 std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::ReferenceStamped::ConstSharedPtr& data);
744 double getHeading(
const mrs_msgs::msg::ReferenceStamped& data);
753 double getHeading(
const mrs_msgs::msg::ReferenceStamped::SharedPtr& data);
762 double getHeading(
const mrs_msgs::msg::ReferenceStamped::ConstSharedPtr& data);
Conversions between various representations of object attitude in 3D. Supports Quaternions,...
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
geometry_msgs::msg::Pose getPose(const nav_msgs::msg::Odometry &data)
returns the Pose part of the nav_msgs::msg::Odometry message
Definition msg_extractor.cpp:292
double getHeading(const geometry_msgs::msg::Pose &data)
get heading from geometry_msgs::msg::Pose
Definition msg_extractor.cpp:78
std::tuple< double, double, double > getVelocity(const geometry_msgs::msg::Twist &data)
get velocity from geometry_msgs::msg::Twist
Definition msg_extractor.cpp:176
std::tuple< double, double, double > getPosition(const geometry_msgs::msg::Pose &data)
get position from geometry_msgs::msg::Pose
Definition msg_extractor.cpp:60
double getYaw(const geometry_msgs::msg::Pose &data)
get yaw from geometry_msgs::msg::Pose
Definition msg_extractor.cpp:96
std::tuple< double, double, double > getXYZ(const geometry_msgs::msg::Point &data)
get XYZ from geometry_msgs::msg::Point
Definition msg_extractor.cpp:8