37 #include <QApplication> 39 #include <pcl/io/pcd_io.h> 40 #include <pcl/io/ply_io.h> 41 #include <pcl/filters/filter.h> 48 "rtabmap-rgbd_mapping driver\n" 49 " 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\n\n");
54 int main(
int argc,
char * argv[])
66 driver = atoi(argv[argc-1]);
67 if(driver < 0 || driver > 8)
69 UERROR(
"driver should be between 0 and 8.");
80 Transform opticalRotation(0,0,1,0, -1,0,0,0, 0,-1,0,0);
85 UERROR(
"Not built with OpenNI2 support...");
94 UERROR(
"Not built with Freenect support...");
103 UERROR(
"Not built with OpenNI from OpenCV support...");
112 UERROR(
"Not built with OpenNI from OpenCV support...");
117 else if (driver == 5)
121 UERROR(
"Not built with Freenect2 support...");
126 else if (driver == 6)
130 UERROR(
"Not built with ZED SDK support...");
133 camera =
new CameraStereoZed(0, 2, 1, 1, 100,
false, 0, opticalRotation);
135 else if (driver == 7)
139 UERROR(
"Not built with RealSense support...");
144 else if (driver == 8)
148 UERROR(
"Not built with RealSense2 support...");
160 UERROR(
"Camera init failed!");
168 QApplication
app(argc, argv);
180 rtabmap->
init(params);
197 rtabmapThread.
start();
199 cameraThread.
start();
211 odomThread.
join(
true);
212 rtabmapThread.
join(
true);
215 printf(
"Saving rtabmap_cloud.pcd...\n");
216 std::map<int, Signature> nodes;
217 std::map<int, Transform> optimizedPoses;
218 std::multimap<int, Link> links;
219 rtabmap->
get3DMap(nodes, optimizedPoses, links,
true,
true);
220 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
221 for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
223 Signature node = nodes.find(iter->first)->second;
233 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(
new pcl::PointCloud<pcl::PointXYZRGB>);
234 std::vector<int> index;
236 if(!tmpNoNaN->empty())
243 printf(
"Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01
f, (
int)cloud->size());
246 printf(
"Saving rtabmap_cloud.pcd... done! (%d points)\n", (
int)cloud->size());
247 pcl::io::savePCDFile(
"rtabmap_cloud.pcd", *cloud);
252 printf(
"Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
256 printf(
"Saving rtabmap_trajectory.txt ...\n");
257 if(optimizedPoses.size() &&
graph::exportPoses(
"rtabmap_trajectory.txt", 0, optimizedPoses, links))
259 printf(
"Saving rtabmap_trajectory.txt... done!\n");
263 printf(
"Saving rtabmap_trajectory.txt... failed!\n");
266 rtabmap->
close(
false);
void get3DMap(std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global) const
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 >(), bool g2oRobust=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
static void setLevel(ULogger::Level level)
static rtabmap::Transform opticalRotation(1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f, 0.0f, 0.0f, 0.0f,-1.0f, 0.0f)
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
void close(bool databaseSaved=true, const std::string &ouputDatabasePath="")
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[])
void init(const ParametersMap ¶meters, const std::string &databasePath="")
void registerToEventsManager()
SensorData & sensorData()
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)