Go to the documentation of this file.00001 #ifndef MRPT_BRIDGE_BEACON_H
00002 #define MRPT_BRIDGE_BEACON_H
00003
00004 #include <stdint.h>
00005 #include <string>
00006
00007 namespace std
00008 {
00009 template <class T>
00010 class allocator;
00011 }
00012
00013 namespace geometry_msgs
00014 {
00015 template <class ContainerAllocator>
00016 struct Pose_;
00017 typedef Pose_<std::allocator<void>> Pose;
00018 }
00019
00020 namespace mrpt_msgs
00021 {
00022 template <class ContainerAllocator>
00023 struct ObservationRangeBeacon_;
00024 typedef ObservationRangeBeacon_<std::allocator<void>> ObservationRangeBeacon;
00025 }
00026
00027 namespace mrpt
00028 {
00029 namespace poses
00030 {
00031 class CPose3D;
00032 }
00033 }
00034 #include <mrpt/version.h>
00035
00036 namespace mrpt
00037 {
00038 namespace obs
00039 {
00040 class CObservationBeaconRanges;
00041 }
00042 }
00043
00044 namespace mrpt_bridge
00045 {
00054 bool convert(
00055 const mrpt_msgs::ObservationRangeBeacon& _msg,
00056 const mrpt::poses::CPose3D& _pose,
00057
00058 mrpt::obs::CObservationBeaconRanges& _obj);
00059
00065 bool convert(
00066
00067 const mrpt::obs::CObservationBeaconRanges& _obj,
00068 mrpt_msgs::ObservationRangeBeacon& _msg);
00069
00076 bool convert(
00077 const mrpt::obs::CObservationBeaconRanges& _obj,
00078 mrpt_msgs::ObservationRangeBeacon& _msg, geometry_msgs::Pose& _pose);
00079
00082 }
00083
00084 #endif // MRPT_BRIDGE_BEACON_H