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>
29std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Point& data);
38std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Point::SharedPtr& data);
47std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Point::ConstSharedPtr& data);
60std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Vector3& data);
69std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Vector3::SharedPtr& data);
78std::tuple<double, double, double>
getXYZ(
const geometry_msgs::msg::Vector3::ConstSharedPtr& data);
93std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::Pose& data);
102std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::Pose::SharedPtr& data);
111std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::Pose::ConstSharedPtr& data);
124double getHeading(
const geometry_msgs::msg::Pose& data);
133double getHeading(
const geometry_msgs::msg::Pose::SharedPtr& data);
142double getHeading(
const geometry_msgs::msg::Pose::ConstSharedPtr& data);
155double getYaw(
const geometry_msgs::msg::Pose& data);
164double getYaw(
const geometry_msgs::msg::Pose::SharedPtr& data);
173double getYaw(
const geometry_msgs::msg::Pose::ConstSharedPtr& data);
190std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::PoseWithCovariance& data);
199std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
208std::tuple<double, double, double>
getPosition(
const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
221double getHeading(
const geometry_msgs::msg::PoseWithCovariance& data);
230double getHeading(
const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
239double getHeading(
const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
252double getYaw(
const geometry_msgs::msg::PoseWithCovariance& data);
261double getYaw(
const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
270double getYaw(
const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
287std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::Twist& data);
296std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::Twist::SharedPtr& data);
305std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::Twist::ConstSharedPtr& data);
322std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::TwistWithCovariance& data);
331std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::TwistWithCovariance::SharedPtr& data);
340std::tuple<double, double, double>
getVelocity(
const geometry_msgs::msg::TwistWithCovariance::ConstSharedPtr& data);
357std::tuple<double, double, double>
getPosition(
const nav_msgs::msg::Odometry& data);
366std::tuple<double, double, double>
getPosition(
const nav_msgs::msg::Odometry::SharedPtr& data);
375std::tuple<double, double, double>
getPosition(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
388std::tuple<double, double, double>
getVelocity(
const nav_msgs::msg::Odometry& data);
397std::tuple<double, double, double>
getVelocity(
const nav_msgs::msg::Odometry::SharedPtr& data);
406std::tuple<double, double, double>
getVelocity(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
420double getHeading(
const nav_msgs::msg::Odometry& data);
429double getHeading(
const nav_msgs::msg::Odometry::SharedPtr& data);
438double getHeading(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
451double getHeading(
const nav_msgs::msg::Odometry& data);
460double getHeading(
const nav_msgs::msg::Odometry::SharedPtr& data);
469double getHeading(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
482double getYaw(
const nav_msgs::msg::Odometry& data);
491double getYaw(
const nav_msgs::msg::Odometry::SharedPtr& data);
500double getYaw(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
513geometry_msgs::msg::Pose
getPose(
const nav_msgs::msg::Odometry& data);
522geometry_msgs::msg::Pose
getPose(
const nav_msgs::msg::Odometry::SharedPtr& data);
531geometry_msgs::msg::Pose
getPose(
const nav_msgs::msg::Odometry::ConstSharedPtr& data);
548std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::TrackerCommand& data);
557std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
566std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
580std::tuple<double, double, double>
getVelocity(
const mrs_msgs::msg::TrackerCommand& data);
589std::tuple<double, double, double>
getVelocity(
const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
598std::tuple<double, double, double>
getVelocity(
const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
612double getHeading(
const mrs_msgs::msg::TrackerCommand& data);
621double getHeading(
const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
630double getHeading(
const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
647std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::Reference& data);
656std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::Reference::SharedPtr& data);
665std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::Reference::ConstSharedPtr& data);
678double getHeading(
const mrs_msgs::msg::Reference& data);
687double getHeading(
const mrs_msgs::msg::Reference::SharedPtr& data);
696double getHeading(
const mrs_msgs::msg::Reference::ConstSharedPtr& data);
713std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::ReferenceStamped& data);
722std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::ReferenceStamped::SharedPtr& data);
731std::tuple<double, double, double>
getPosition(
const mrs_msgs::msg::ReferenceStamped::ConstSharedPtr& data);
744double getHeading(
const mrs_msgs::msg::ReferenceStamped& data);
753double getHeading(
const mrs_msgs::msg::ReferenceStamped::SharedPtr& data);
762double 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:250
double getHeading(const geometry_msgs::msg::Pose &data)
get heading from geometry_msgs::msg::Pose
Definition msg_extractor.cpp:69
std::tuple< double, double, double > getVelocity(const geometry_msgs::msg::Twist &data)
get velocity from geometry_msgs::msg::Twist
Definition msg_extractor.cpp:152
std::tuple< double, double, double > getPosition(const geometry_msgs::msg::Pose &data)
get position from geometry_msgs::msg::Pose
Definition msg_extractor.cpp:54
double getYaw(const geometry_msgs::msg::Pose &data)
get yaw from geometry_msgs::msg::Pose
Definition msg_extractor.cpp:84
std::tuple< double, double, double > getXYZ(const geometry_msgs::msg::Point &data)
get XYZ from geometry_msgs::msg::Point
Definition msg_extractor.cpp:8