landmark.h
Go to the documentation of this file.
00001 /*
00002  * File: landmark.h
00003  * Author: Vladislav Tananaev
00004  *
00005  */
00006 
00007 #ifndef MRPT_BRIDGE_LANDMARK_H
00008 #define MRPT_BRIDGE_LANDMARK_H
00009 
00010 #include <stdint.h>
00011 #include <string>
00012 
00013 namespace std
00014 {
00015 template <class T>
00016 class allocator;
00017 }
00018 
00019 namespace geometry_msgs
00020 {
00021 template <class ContainerAllocator>
00022 struct Pose_;
00023 typedef Pose_<std::allocator<void>> Pose;
00024 }
00025 
00026 namespace mrpt_msgs
00027 {
00028 template <class ContainerAllocator>
00029 struct ObservationRangeBearing_;
00030 typedef ObservationRangeBearing_<std::allocator<void>> ObservationRangeBearing;
00031 }
00032 
00033 namespace mrpt
00034 {
00035 namespace poses
00036 {
00037 class CPose3D;
00038 }
00039 }
00040 #include <mrpt/version.h>
00041 
00042 namespace mrpt
00043 {
00044 namespace obs
00045 {
00046 class CObservationBearingRange;
00047 }
00048 }
00049 
00050 namespace mrpt_bridge
00051 {
00060 bool convert(
00061         const mrpt_msgs::ObservationRangeBearing& _msg,
00062         const mrpt::poses::CPose3D& _pose, mrpt::obs::CObservationBearingRange& _obj
00063 
00064         );
00065 
00071 bool convert(
00072         const mrpt::obs::CObservationBearingRange& _obj,
00073         mrpt_msgs::ObservationRangeBearing& _msg);
00074 
00081 bool convert(
00082         const mrpt::obs::CObservationBearingRange& _obj,
00083         mrpt_msgs::ObservationRangeBearing& _msg, geometry_msgs::Pose& _pose);
00084 
00087 }  // namespace mrpt_bridge
00088 
00089 #endif  // MRPT_BRIDGE_LANDMARK_H


mrpt_bridge
Author(s): Markus Bader , Raphael Zack
autogenerated on Mon Sep 18 2017 03:12:06