#include <ros/ros.h>#include <rosbag/bag.h>#include <rosbag/view.h>#include <pcl/point_types.h>#include <pcl/point_cloud.h>#include <pcl/io/pcd_io.h>#include <pcl/registration/transforms.h>#include <cob_3d_mapping_slam/curved_polygons/debug_interface.h>#include <cob_3d_mapping_slam/slam/context.h>#include <cob_3d_mapping_slam/slam/node.h>#include <cob_3d_mapping_slam/dof/tflink.h>#include <cob_3d_mapping_slam/dof/dof_uncertainty.h>#include <cob_3d_mapping_slam/dof/dof_variance.h>#include <cob_3d_mapping_slam/slam/dummy/objctxt.h>#include <cob_3d_mapping_slam/slam/dummy/registration.h>#include <cob_3d_mapping_slam/slam/dummy/key.h>#include <cob_3d_mapping_slam/slam/dummy/robot.h>#include <cob_3d_mapping_slam/curved_polygons/objctxt.h>#include <cob_3d_mapping_slam/curved_polygons/key.h>#include <cob_3d_mapping_msgs/ShapeArray.h>#include "gnuplot_i.hpp"#include <gtest/gtest.h>#include <boost/random/mersenne_twister.hpp>#include <boost/random/uniform_real.hpp>#include <boost/random/variate_generator.hpp>#include <visualization_msgs/Marker.h>#include <nav_msgs/Odometry.h>#include "pcl/visualization/pcl_visualizer.h"#include <pcl/visualization/cloud_viewer.h>
Go to the source code of this file.
Classes | |
| struct | SOdomotry_Data |
Defines | |
| #define | CYCLES 100 |
| #define | DEBUG_ |
Typedefs | |
| typedef void(* | motion_fct )(Eigen::Matrix3f &, Eigen::Vector3f &) |
Functions | |
| float | gen_random_float (float min, float max) |
| std::vector < cob_3d_mapping_msgs::CurvedPolygon > | generateRandomPlanes (const int N, const bool cors) |
| template<typename Matrix > | |
| float | MATRIX_DISTANCE (const Matrix &a, const Matrix &b, const float thr=0.05) |
| void | motion1 (Eigen::Matrix3f &rot, Eigen::Vector3f &tr) |
| void | motion2 (Eigen::Matrix3f &rot, Eigen::Vector3f &tr) |
| void | motion2s (Eigen::Matrix3f &rot, Eigen::Vector3f &tr) |
| void | motion3 (Eigen::Matrix3f &rot, Eigen::Vector3f &tr) |
| void | motion3s (Eigen::Matrix3f &rot, Eigen::Vector3f &tr) |
| void | motion4 (Eigen::Matrix3f &rot, Eigen::Vector3f &tr) |
| void | motion4s (Eigen::Matrix3f &rot, Eigen::Vector3f &tr) |
| void | t1 () |
| void | t2 () |
| void | t4 () |
| TEST (Slam, merging) | |
Variables | |
| static const char * | BAGFILES [][512] |
| static const char * | GROUNDTRUTH [][512] |
| #define CYCLES 100 |
Definition at line 55 of file slam_dummy.cpp.
| #define DEBUG_ |
Definition at line 20 of file slam_dummy.cpp.
| typedef void(* motion_fct)(Eigen::Matrix3f &, Eigen::Vector3f &) |
Definition at line 219 of file slam_dummy.cpp.
| float gen_random_float | ( | float | min, |
| float | max | ||
| ) |
Definition at line 140 of file slam_dummy.cpp.
| std::vector<cob_3d_mapping_msgs::CurvedPolygon> generateRandomPlanes | ( | const int | N, |
| const bool | cors | ||
| ) |
Definition at line 149 of file slam_dummy.cpp.
| float MATRIX_DISTANCE | ( | const Matrix & | a, |
| const Matrix & | b, | ||
| const float | thr = 0.05 |
||
| ) |
Definition at line 88 of file slam_dummy.cpp.
| void motion1 | ( | Eigen::Matrix3f & | rot, |
| Eigen::Vector3f & | tr | ||
| ) |
Definition at line 221 of file slam_dummy.cpp.
| void motion2 | ( | Eigen::Matrix3f & | rot, |
| Eigen::Vector3f & | tr | ||
| ) |
Definition at line 227 of file slam_dummy.cpp.
| void motion2s | ( | Eigen::Matrix3f & | rot, |
| Eigen::Vector3f & | tr | ||
| ) |
Definition at line 235 of file slam_dummy.cpp.
| void motion3 | ( | Eigen::Matrix3f & | rot, |
| Eigen::Vector3f & | tr | ||
| ) |
Definition at line 241 of file slam_dummy.cpp.
| void motion3s | ( | Eigen::Matrix3f & | rot, |
| Eigen::Vector3f & | tr | ||
| ) |
Definition at line 253 of file slam_dummy.cpp.
| void motion4 | ( | Eigen::Matrix3f & | rot, |
| Eigen::Vector3f & | tr | ||
| ) |
Definition at line 261 of file slam_dummy.cpp.
| void motion4s | ( | Eigen::Matrix3f & | rot, |
| Eigen::Vector3f & | tr | ||
| ) |
Definition at line 269 of file slam_dummy.cpp.
| void t1 | ( | ) |
Definition at line 121 of file slam_dummy.cpp.
| void t2 | ( | ) |
Definition at line 103 of file slam_dummy.cpp.
| void t4 | ( | ) |
Definition at line 278 of file slam_dummy.cpp.
| TEST | ( | Slam | , |
| merging | |||
| ) |
Definition at line 379 of file slam_dummy.cpp.
const char* BAGFILES[][512] [static] |
{
{
"test/cp3_rgbd_dataset_freiburg2_xyz.bag",
""}
}
Definition at line 56 of file slam_dummy.cpp.
const char* GROUNDTRUTH[][512] [static] |
{
{
"test/rgbd_dataset_freiburg2_xyz-groundtruth.txt",
0
}
}
Definition at line 76 of file slam_dummy.cpp.