37 #include <QApplication> 39 #include <pcl/io/pcd_io.h> 40 #include <pcl/io/ply_io.h> 41 #include <pcl/filters/filter.h> 52 "rtabmap-rgbd_mapping driver\n" 53 " driver Driver number to use: 0=OpenNI-PCL, 1=OpenNI2, 2=Freenect, 3=OpenNI-CV, 4=OpenNI-CV-ASUS, 5=Freenect2, 6=ZED SDK, 7=RealSense, 8=RealSense2 9=Kinect for Azure SDK 10=MYNT EYE S\n\n");
74 driver = atoi(argv[argc-1]);
75 if(driver < 0 || driver > 10)
77 UERROR(
"driver should be between 0 and 10.");
92 UERROR(
"Not built with OpenNI2 support...");
101 UERROR(
"Not built with Freenect support...");
110 UERROR(
"Not built with OpenNI from OpenCV support...");
119 UERROR(
"Not built with OpenNI from OpenCV support...");
124 else if (driver == 5)
128 UERROR(
"Not built with Freenect2 support...");
133 else if (driver == 6)
137 UERROR(
"Not built with ZED SDK support...");
142 else if (driver == 7)
146 UERROR(
"Not built with RealSense support...");
151 else if (driver == 8)
155 UERROR(
"Not built with RealSense2 support...");
160 else if (driver == 9)
164 UERROR(
"Not built with Kinect for Azure SDK support...");
169 else if (driver == 10)
173 UERROR(
"Not built with Mynt Eye S support...");
185 UERROR(
"Camera init failed!");
193 QApplication
app(argc, argv);
205 rtabmap->
init(params);
222 rtabmapThread.
start();
224 cameraThread.
start();
236 odomThread.
join(
true);
237 rtabmapThread.
join(
true);
240 printf(
"Saving rtabmap_cloud.pcd...\n");
241 std::map<int, Signature> nodes;
242 std::map<int, Transform> optimizedPoses;
243 std::multimap<int, Link> links;
244 rtabmap->
getGraph(optimizedPoses, links,
true,
true, &nodes,
true,
true,
true,
true);
245 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
246 for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
248 Signature node = nodes.find(iter->first)->second;
258 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(
new pcl::PointCloud<pcl::PointXYZRGB>);
259 std::vector<int> index;
261 if(!tmpNoNaN->empty())
268 printf(
"Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01
f, (
int)cloud->size());
271 printf(
"Saving rtabmap_cloud.pcd... done! (%d points)\n", (
int)cloud->size());
272 pcl::io::savePCDFile(
"rtabmap_cloud.pcd", *cloud);
277 printf(
"Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
281 printf(
"Saving rtabmap_trajectory.txt ...\n");
282 if(optimizedPoses.size() &&
graph::exportPoses(
"rtabmap_trajectory.txt", 0, optimizedPoses, links))
284 printf(
"Saving rtabmap_trajectory.txt... done!\n");
288 printf(
"Saving rtabmap_trajectory.txt... failed!\n");
291 rtabmap->
close(
false);
static void createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
std::map< std::string, std::string > ParametersMap
void init(const ParametersMap ¶meters, const std::string &databasePath="", bool loadDatabaseParameters=false)
static void setLevel(ULogger::Level level)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
static Odometry * create(const ParametersMap ¶meters=ParametersMap())
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
int main(int argc, char *argv[])
bool RTABMAP_EXP exportPoses(const std::string &filePath, int format, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints=std::multimap< int, Link >(), const std::map< int, double > &stamps=std::map< int, double >(), const ParametersMap ¶meters=ParametersMap())
void registerToEventsManager()
SensorData & sensorData()
void getGraph(std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global, std::map< int, Signature > *signatures=0, bool withImages=false, bool withScan=false, bool withUserData=false, bool withGrid=false, bool withWords=true, bool withGlobalDescriptors=true) const
void unregisterFromEventsManager()
void join(bool killFirst=false)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)