marker_msgs.h
Go to the documentation of this file.
00001 
00009 #ifndef MRPT_BRIDGE_MARKER_MSGS_H
00010 #define MRPT_BRIDGE_MARKER_MSGS_H
00011 
00012 #include <marker_msgs/MarkerDetection.h>
00013 #include <mrpt/obs/CObservationRange.h>
00014 #include <mrpt/obs/CObservation2DRangeScan.h>
00015 #include <mrpt/obs/CObservationBearingRange.h>
00016 #include <mrpt/obs/CObservationBeaconRanges.h>
00017 
00018 
00019 namespace std
00020 {
00021 template <class T>
00022 class allocator;
00023 }
00024 
00025 namespace geometry_msgs
00026 {
00027 template <class ContainerAllocator>
00028 struct Pose_;
00029 typedef Pose_<std::allocator<void>> Pose;
00030 }
00031 
00032 namespace marker_msgs
00033 {
00034 template <class ContainerAllocator>
00035 struct MarkerDetection_;
00036 typedef MarkerDetection_<std::allocator<void>> MarkerDetection;
00037 }
00038 
00039 namespace mrpt
00040 {
00041 namespace poses
00042 {
00043 class CPose3D;
00044 }
00045 }
00046 
00047 #include <mrpt/version.h>
00048 namespace mrpt
00049 {
00050 namespace obs
00051 {
00052 class CObservationBearingRange;
00053 }
00054 }
00055 
00056 namespace mrpt_bridge
00057 {
00058     
00059     bool convert(const marker_msgs::MarkerDetection& _msg, const mrpt::poses::CPose3D& _pose, mrpt::obs::CObservationBearingRange& _obj);
00060     bool convert(const marker_msgs::MarkerDetection& _msg, const mrpt::poses::CPose3D& _pose, mrpt::obs::CObservationBeaconRanges& _obj);
00061 }
00062 
00063 #endif //MRPT_BRIDGE_MARKER_MSGS_H


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