Go to the documentation of this file.
36 #include <QApplication>
38 #include <pcl/io/pcd_io.h>
39 #include <pcl/io/ply_io.h>
40 #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!");
222 rtabmapThread.
start();
224 cameraThread.
start();
226 printf(
"Press Space key to pause.\n");
238 odomThread.
join(
true);
239 rtabmapThread.
join(
true);
242 printf(
"Saving rtabmap_cloud.pcd...\n");
243 std::map<int, Signature>
nodes;
244 std::map<int, Transform> optimizedPoses;
245 std::multimap<int, Link> links;
246 rtabmap->getGraph(optimizedPoses, links,
true,
true, &
nodes,
true,
true,
true,
true);
247 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
248 for(std::map<int, Transform>::iterator
iter=optimizedPoses.begin();
iter!=optimizedPoses.end(); ++
iter)
260 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmpNoNaN(
new pcl::PointCloud<pcl::PointXYZRGB>);
261 std::vector<int> index;
263 if(!tmpNoNaN->empty())
270 printf(
"Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01
f, (
int)cloud->size());
273 printf(
"Saving rtabmap_cloud.pcd... done! (%d points)\n", (
int)cloud->size());
274 pcl::io::savePCDFile(
"rtabmap_cloud.pcd", *cloud);
279 printf(
"Saving rtabmap_cloud.pcd... failed! The cloud is empty.\n");
283 printf(
"Saving rtabmap_trajectory.txt ...\n");
284 if(optimizedPoses.size() &&
graph::exportPoses(
"rtabmap_trajectory.txt", 0, optimizedPoses, links))
286 printf(
"Saving rtabmap_trajectory.txt... done!\n");
290 printf(
"Saving rtabmap_trajectory.txt... failed!\n");
static Odometry * create(const ParametersMap ¶meters=ParametersMap())
int main(int argc, char *argv[])
void registerToEventsManager()
bool RTABMAP_CORE_EXPORT 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())
static void setLevel(ULogger::Level level)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
void join(bool killFirst=false)
std::map< std::string, std::string > ParametersMap
virtual bool init(const std::string &calibrationFolder=".", const std::string &cameraName="")=0
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT 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 createPipe(const UEventsSender *sender, const UEventsHandler *receiver, const std::string &eventName)
void unregisterFromEventsManager()
SmartProjectionParams params(gtsam::HESSIAN, gtsam::ZERO_ON_DEGENERACY)
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
iterator iter(handle obj)
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)), Cal3Bundler0(1, 0, 0))
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
SensorData & sensorData()
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:11