mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
msg_extractor.h
Go to the documentation of this file.
1// clang: TomasFormat
6#ifndef MRS_LIB_MSG_EXTRACTOR_H
7#define MRS_LIB_MSG_EXTRACTOR_H
8
9#include <mrs_msgs/msg/reference.hpp>
10#include <mrs_msgs/msg/reference_stamped.hpp>
11#include <mrs_msgs/msg/tracker_command.hpp>
12
13#include <nav_msgs/msg/odometry.hpp>
14
16
17namespace mrs_lib
18{
19
20/* geometry_msgs::msg::Point //{ */
21
29std::tuple<double, double, double> getXYZ(const geometry_msgs::msg::Point& data);
30
38std::tuple<double, double, double> getXYZ(const geometry_msgs::msg::Point::SharedPtr& data);
39
47std::tuple<double, double, double> getXYZ(const geometry_msgs::msg::Point::ConstSharedPtr& data);
48
49//}
50
51/* geometry_msgs::msg::Vector3 //{ */
52
60std::tuple<double, double, double> getXYZ(const geometry_msgs::msg::Vector3& data);
61
69std::tuple<double, double, double> getXYZ(const geometry_msgs::msg::Vector3::SharedPtr& data);
70
78std::tuple<double, double, double> getXYZ(const geometry_msgs::msg::Vector3::ConstSharedPtr& data);
79
80//}
81
82/* geometry_msgs::msg::Pose //{ */
83
84/* getPosition() //{ */
85
93std::tuple<double, double, double> getPosition(const geometry_msgs::msg::Pose& data);
94
102std::tuple<double, double, double> getPosition(const geometry_msgs::msg::Pose::SharedPtr& data);
103
111std::tuple<double, double, double> getPosition(const geometry_msgs::msg::Pose::ConstSharedPtr& data);
112
113//}
114
115/* getHeading() //{ */
116
124double getHeading(const geometry_msgs::msg::Pose& data);
125
133double getHeading(const geometry_msgs::msg::Pose::SharedPtr& data);
134
142double getHeading(const geometry_msgs::msg::Pose::ConstSharedPtr& data);
143
144//}
145
146/* getYaw() //{ */
147
155double getYaw(const geometry_msgs::msg::Pose& data);
156
164double getYaw(const geometry_msgs::msg::Pose::SharedPtr& data);
165
173double getYaw(const geometry_msgs::msg::Pose::ConstSharedPtr& data);
174
175//}
176
177//}
178
179/* geometry_msgs::msg::PoseWithCovariance //{ */
180
181/* getPosition() //{ */
182
190std::tuple<double, double, double> getPosition(const geometry_msgs::msg::PoseWithCovariance& data);
191
199std::tuple<double, double, double> getPosition(const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
200
208std::tuple<double, double, double> getPosition(const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
209
210//}
211
212/* getHeading() //{ */
213
221double getHeading(const geometry_msgs::msg::PoseWithCovariance& data);
222
230double getHeading(const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
231
239double getHeading(const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
240
241//}
242
243/* getYaw() //{ */
244
252double getYaw(const geometry_msgs::msg::PoseWithCovariance& data);
253
261double getYaw(const geometry_msgs::msg::PoseWithCovariance::SharedPtr& data);
262
270double getYaw(const geometry_msgs::msg::PoseWithCovariance::ConstSharedPtr& data);
271
272//}
273
274//}
275
276/* geometry_msgs::msg::Twist //{ */
277
278/* getVelocity() //{ */
279
287std::tuple<double, double, double> getVelocity(const geometry_msgs::msg::Twist& data);
288
296std::tuple<double, double, double> getVelocity(const geometry_msgs::msg::Twist::SharedPtr& data);
297
305std::tuple<double, double, double> getVelocity(const geometry_msgs::msg::Twist::ConstSharedPtr& data);
306
307//}
308
309//}
310
311/* geometry_msgs::msg::TwistWithCovariance //{ */
312
313/* getVelocity() //{ */
314
322std::tuple<double, double, double> getVelocity(const geometry_msgs::msg::TwistWithCovariance& data);
323
331std::tuple<double, double, double> getVelocity(const geometry_msgs::msg::TwistWithCovariance::SharedPtr& data);
332
340std::tuple<double, double, double> getVelocity(const geometry_msgs::msg::TwistWithCovariance::ConstSharedPtr& data);
341
342//}
343
344//}
345
346/* nav_msgs::msg::Odometry //{ */
347
348/* getPosition() //{ */
349
357std::tuple<double, double, double> getPosition(const nav_msgs::msg::Odometry& data);
358
366std::tuple<double, double, double> getPosition(const nav_msgs::msg::Odometry::SharedPtr& data);
367
375std::tuple<double, double, double> getPosition(const nav_msgs::msg::Odometry::ConstSharedPtr& data);
376
377//}
378
379/* getVelocity() //{ */
380
388std::tuple<double, double, double> getVelocity(const nav_msgs::msg::Odometry& data);
389
397std::tuple<double, double, double> getVelocity(const nav_msgs::msg::Odometry::SharedPtr& data);
398
406std::tuple<double, double, double> getVelocity(const nav_msgs::msg::Odometry::ConstSharedPtr& data);
407
408
409//}
410
411/* getHeading() //{ */
412
420double getHeading(const nav_msgs::msg::Odometry& data);
421
429double getHeading(const nav_msgs::msg::Odometry::SharedPtr& data);
430
438double getHeading(const nav_msgs::msg::Odometry::ConstSharedPtr& data);
439
440//}
441
442/* getHeading() //{ */
443
451double getHeading(const nav_msgs::msg::Odometry& data);
452
460double getHeading(const nav_msgs::msg::Odometry::SharedPtr& data);
461
469double getHeading(const nav_msgs::msg::Odometry::ConstSharedPtr& data);
470
471//}
472
473/* getYaw() //{ */
474
482double getYaw(const nav_msgs::msg::Odometry& data);
483
491double getYaw(const nav_msgs::msg::Odometry::SharedPtr& data);
492
500double getYaw(const nav_msgs::msg::Odometry::ConstSharedPtr& data);
501
502//}
503
504/* getPose() //{ */
505
513geometry_msgs::msg::Pose getPose(const nav_msgs::msg::Odometry& data);
514
522geometry_msgs::msg::Pose getPose(const nav_msgs::msg::Odometry::SharedPtr& data);
523
531geometry_msgs::msg::Pose getPose(const nav_msgs::msg::Odometry::ConstSharedPtr& data);
532
533//}
534
535//}
536
537/* mrs_msgs::msg::TrackerCommand //{ */
538
539/* getPosition() //{ */
540
548std::tuple<double, double, double> getPosition(const mrs_msgs::msg::TrackerCommand& data);
549
557std::tuple<double, double, double> getPosition(const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
558
566std::tuple<double, double, double> getPosition(const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
567
568
569//}
570
571/* getVelocity() //{ */
572
580std::tuple<double, double, double> getVelocity(const mrs_msgs::msg::TrackerCommand& data);
581
589std::tuple<double, double, double> getVelocity(const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
590
598std::tuple<double, double, double> getVelocity(const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
599
600
601//}
602
603/* getHeading() //{ */
604
612double getHeading(const mrs_msgs::msg::TrackerCommand& data);
613
621double getHeading(const mrs_msgs::msg::TrackerCommand::SharedPtr& data);
622
630double getHeading(const mrs_msgs::msg::TrackerCommand::ConstSharedPtr& data);
631
632//}
633
634//}
635
636/* mrs_msgs::msg::Reference //{ */
637
638/* getPosition() //{ */
639
647std::tuple<double, double, double> getPosition(const mrs_msgs::msg::Reference& data);
648
656std::tuple<double, double, double> getPosition(const mrs_msgs::msg::Reference::SharedPtr& data);
657
665std::tuple<double, double, double> getPosition(const mrs_msgs::msg::Reference::ConstSharedPtr& data);
666
667//}
668
669/* getHeading() //{ */
670
678double getHeading(const mrs_msgs::msg::Reference& data);
679
687double getHeading(const mrs_msgs::msg::Reference::SharedPtr& data);
688
696double getHeading(const mrs_msgs::msg::Reference::ConstSharedPtr& data);
697
698//}
699
700//}
701
702/* mrs_msgs::msg::ReferenceStamped //{ */
703
704/* getPosition() //{ */
705
713std::tuple<double, double, double> getPosition(const mrs_msgs::msg::ReferenceStamped& data);
714
722std::tuple<double, double, double> getPosition(const mrs_msgs::msg::ReferenceStamped::SharedPtr& data);
723
731std::tuple<double, double, double> getPosition(const mrs_msgs::msg::ReferenceStamped::ConstSharedPtr& data);
732
733//}
734
735/* getHeading() //{ */
736
744double getHeading(const mrs_msgs::msg::ReferenceStamped& data);
745
753double getHeading(const mrs_msgs::msg::ReferenceStamped::SharedPtr& data);
754
762double getHeading(const mrs_msgs::msg::ReferenceStamped::ConstSharedPtr& data);
763
764//}
765
766//}
767
768} // namespace mrs_lib
769
770//}
771
772#endif // MRS_LIB_MSG_EXTRACTOR_H
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