| Classes | |
| struct | DualFloat | 
| struct | Polyline | 
| Public Member Functions | |
| float | calc_error (const pcl::PointCloud< Point > &s, const pcl::PointCloud< Point > &t) | 
| void | commandCallback (const std_msgs::String::ConstPtr &msg) | 
| float | findCorr (pcl::PointCloud< Point > &pc_old, const pcl::PointCloud< Point > &pc_new, std::vector< int > &cor_inds) | 
| int | getBest (const pcl::PointCloud< Point > &pc, const int ind, const float diff) | 
| int | getI (const int ind, unsigned char *depth_map, const pcl::PointCloud< Point > &pc) | 
| float | getMaxDiff (const pcl::PointCloud< Point > &pc, const int ind) | 
| float | getMaxDiff2 (const pcl::PointCloud< Point > &pc, const int ind, const pcl::PointCloud< Point > &pc2, int &mi) | 
| int | getNearest (const pcl::PointCloud< Point > &pc, const pcl::PointCloud< Point > &pc2, const int ind, const float diff) | 
| void | pointCloudSubCallback (const sensor_msgs::PointCloud2ConstPtr &pc_in) | 
| void | publishMarkerPoint (const Point &p, int id, float r, float g, float b, float Size=0.02) | 
| TestNode () | |
| ~TestNode () | |
| Static Public Member Functions | |
| static void | publishLineMarker (const std::vector< Eigen::Vector4f > &pl, const int id=rand()%111111) | 
| static void | publishLineMarker (Eigen::Vector3f a, Eigen::Vector3f b, const int id=rand()%111111) | 
| static void | publishTextMarker (const Eigen::Vector3f pos, const std::string &text, const int id=rand()%111111) | 
| Protected Attributes | |
| ros::NodeHandle | n_ | 
| ros::Subscriber | point_cloud_sub_ | 
| Private Types | |
| typedef pcl::PointXYZRGB | Point | 
| Static Private Member Functions | |
| static void | eigen2point (Point &p, const Eigen::Vector3f &e) | 
| static void | point2eigen (Eigen::Vector3f &e, const Point &p) | 
| static void | point2eigen (Eigen::VectorXf &e, const Point &p) | 
| static void | point2eigen (Eigen::Vector4f &e, const Point &p) | 
| Private Attributes | |
| int | factor_ | 
| float | max_alpha_ | 
| float | max_alpha_factor_ | 
| float | min_alpha_ | 
| float | min_alpha_factor_ | 
| float | min_thr_ | 
| float | min_thr_factor_ | 
| Point | movement_overall | 
| Eigen::Vector3f | movement_rotation | 
| Eigen::Matrix3f | old_q_ | 
| Eigen::Vector3f | old_t_ | 
| ros::Subscriber | settings_sub | 
| bool | show_labels_ | 
| bool | show_markers_ | 
Definition at line 2736 of file frir_freehand.cpp.
| typedef pcl::PointXYZRGB TestNode::Point  [private] | 
Definition at line 2739 of file frir_freehand.cpp.
| TestNode::TestNode | ( | ) |  [inline] | 
Definition at line 3147 of file frir_freehand.cpp.
| TestNode::~TestNode | ( | ) |  [inline] | 
void
Definition at line 3227 of file frir_freehand.cpp.
| float TestNode::calc_error | ( | const pcl::PointCloud< Point > & | s, | 
| const pcl::PointCloud< Point > & | t | ||
| ) |  [inline] | 
Definition at line 4224 of file frir_freehand.cpp.
| void TestNode::commandCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |  [inline] | 
Definition at line 3219 of file frir_freehand.cpp.
| static void TestNode::eigen2point | ( | Point & | p, | 
| const Eigen::Vector3f & | e | ||
| ) |  [inline, static, private] | 
Definition at line 2744 of file frir_freehand.cpp.
| float TestNode::findCorr | ( | pcl::PointCloud< Point > & | pc_old, | 
| const pcl::PointCloud< Point > & | pc_new, | ||
| std::vector< int > & | cor_inds | ||
| ) |  [inline] | 
Definition at line 4339 of file frir_freehand.cpp.
| int TestNode::getBest | ( | const pcl::PointCloud< Point > & | pc, | 
| const int | ind, | ||
| const float | diff | ||
| ) |  [inline] | 
Definition at line 4319 of file frir_freehand.cpp.
| int TestNode::getI | ( | const int | ind, | 
| unsigned char * | depth_map, | ||
| const pcl::PointCloud< Point > & | pc | ||
| ) |  [inline] | 
Definition at line 4206 of file frir_freehand.cpp.
| float TestNode::getMaxDiff | ( | const pcl::PointCloud< Point > & | pc, | 
| const int | ind | ||
| ) |  [inline] | 
Definition at line 4232 of file frir_freehand.cpp.
| float TestNode::getMaxDiff2 | ( | const pcl::PointCloud< Point > & | pc, | 
| const int | ind, | ||
| const pcl::PointCloud< Point > & | pc2, | ||
| int & | mi | ||
| ) |  [inline] | 
Definition at line 4252 of file frir_freehand.cpp.
| int TestNode::getNearest | ( | const pcl::PointCloud< Point > & | pc, | 
| const pcl::PointCloud< Point > & | pc2, | ||
| const int | ind, | ||
| const float | diff | ||
| ) |  [inline] | 
Definition at line 4278 of file frir_freehand.cpp.
| static void TestNode::point2eigen | ( | Eigen::Vector3f & | e, | 
| const Point & | p | ||
| ) |  [inline, static, private] | 
Definition at line 2750 of file frir_freehand.cpp.
| static void TestNode::point2eigen | ( | Eigen::VectorXf & | e, | 
| const Point & | p | ||
| ) |  [inline, static, private] | 
Definition at line 2756 of file frir_freehand.cpp.
| static void TestNode::point2eigen | ( | Eigen::Vector4f & | e, | 
| const Point & | p | ||
| ) |  [inline, static, private] | 
Definition at line 2762 of file frir_freehand.cpp.
| void TestNode::pointCloudSubCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | pc_in | ) |  [inline] | 
Definition at line 3237 of file frir_freehand.cpp.
| static void TestNode::publishLineMarker | ( | const std::vector< Eigen::Vector4f > & | pl, | 
| const int | id = rand()%111111 | ||
| ) |  [inline, static] | 
Definition at line 4960 of file frir_freehand.cpp.
| static void TestNode::publishLineMarker | ( | Eigen::Vector3f | a, | 
| Eigen::Vector3f | b, | ||
| const int | id = rand()%111111 | ||
| ) |  [inline, static] | 
Definition at line 5000 of file frir_freehand.cpp.
| void TestNode::publishMarkerPoint | ( | const Point & | p, | 
| int | id, | ||
| float | r, | ||
| float | g, | ||
| float | b, | ||
| float | Size = 0.02 | ||
| ) |  [inline] | 
Definition at line 4885 of file frir_freehand.cpp.
| static void TestNode::publishTextMarker | ( | const Eigen::Vector3f | pos, | 
| const std::string & | text, | ||
| const int | id = rand()%111111 | ||
| ) |  [inline, static] | 
Definition at line 4920 of file frir_freehand.cpp.
| int TestNode::factor_  [private] | 
Definition at line 3142 of file frir_freehand.cpp.
| float TestNode::max_alpha_  [private] | 
Definition at line 3140 of file frir_freehand.cpp.
| float TestNode::max_alpha_factor_  [private] | 
Definition at line 3143 of file frir_freehand.cpp.
| float TestNode::min_alpha_  [private] | 
Definition at line 3140 of file frir_freehand.cpp.
| float TestNode::min_alpha_factor_  [private] | 
Definition at line 3143 of file frir_freehand.cpp.
| float TestNode::min_thr_  [private] | 
Definition at line 3141 of file frir_freehand.cpp.
| float TestNode::min_thr_factor_  [private] | 
Definition at line 3143 of file frir_freehand.cpp.
| Point TestNode::movement_overall  [private] | 
Definition at line 3130 of file frir_freehand.cpp.
| Eigen::Vector3f TestNode::movement_rotation  [private] | 
Definition at line 3131 of file frir_freehand.cpp.
| ros::NodeHandle TestNode::n_  [protected] | 
Definition at line 5045 of file frir_freehand.cpp.
| Eigen::Matrix3f TestNode::old_q_  [private] | 
Definition at line 3132 of file frir_freehand.cpp.
| Eigen::Vector3f TestNode::old_t_  [private] | 
Definition at line 3131 of file frir_freehand.cpp.
| ros::Subscriber TestNode::point_cloud_sub_  [protected] | 
Definition at line 5044 of file frir_freehand.cpp.
| ros::Subscriber TestNode::settings_sub  [private] | 
Definition at line 3134 of file frir_freehand.cpp.
| bool TestNode::show_labels_  [private] | 
Definition at line 3135 of file frir_freehand.cpp.
| bool TestNode::show_markers_  [private] | 
Definition at line 3135 of file frir_freehand.cpp.