Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #ifndef FLIRTLIB_ROS_CONVERSIONS_H
00040 #define FLIRTLIB_ROS_CONVERSIONS_H
00041
00042 #include "flirtlib.h"
00043 #include <flirtlib_ros/ScanMap.h>
00044 #include <sensor_msgs/LaserScan.h>
00045 #include <visualization_msgs/Marker.h>
00046 #include <geometry_msgs/Pose.h>
00047
00048
00049 namespace flirtlib_ros
00050 {
00051
00053 boost::shared_ptr<LaserReading> fromRos(const sensor_msgs::LaserScan& scan);
00054
00058 visualization_msgs::Marker interestPointMarkers (const std::vector<InterestPoint*>& pts,
00059 const geometry_msgs::Pose& pose,
00060 unsigned id=0);
00061
00062
00064 std::vector<visualization_msgs::Marker> poseMarkers (const std::vector<geometry_msgs::Pose>& poses);
00065
00067 InterestPointRos toRos (const InterestPoint& pt);
00068
00071 InterestPoint* fromRos (const InterestPointRos& m);
00072
00076 struct RefScan
00077 {
00078 sensor_msgs::LaserScan::ConstPtr scan;
00079 geometry_msgs::Pose pose;
00080 std::vector<boost::shared_ptr<InterestPoint> > pts;
00081 std::vector<InterestPoint*> raw_pts;
00082
00083 RefScan (sensor_msgs::LaserScan::ConstPtr scan,
00084 const geometry_msgs::Pose& pose,
00085 std::vector<InterestPoint*>& pts);
00086
00087 };
00088
00090 RefScanRos toRos (const RefScan& r);
00091
00093 RefScan fromRos (const RefScanRos& r);
00094
00096 std::vector<RefScan> fromRos (const ScanMap& scan_map);
00097
00099 ScanMap toRos (const std::vector<RefScan>& scans);
00100
00101
00102 }
00103
00104 #endif // include guard