Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #ifndef _scans_2_odom_alg_node_h_
00026 #define _scans_2_odom_alg_node_h_
00027
00028 #include <Eigen/Dense>
00029 #include <iri_base_algorithm/iri_base_algorithm.h>
00030 #include "scans_2_odom_alg.h"
00031 #include <tf/transform_datatypes.h>
00032
00033
00034 #include <sensor_msgs/LaserScan.h>
00035 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00036
00037
00038 #include <iri_poseslam/GetLink.h>
00039 #include <iri_laser_icp/GetRelativePose.h>
00040
00041
00042
00043 using namespace Eigen;
00044
00049 class Scans2OdomAlgNode : public algorithm_base::IriBaseAlgorithm<Scans2OdomAlgorithm>
00050 {
00051 private:
00052
00053
00054
00055 ros::Subscriber scan_subscriber_;
00056 void scan_callback(const sensor_msgs::LaserScan::ConstPtr& msg);
00057
00058
00059 ros::ServiceServer get_link_server_;
00060 bool get_linkCallback(iri_poseslam::GetLink::Request &req, iri_poseslam::GetLink::Response &res);
00061
00062
00063 ros::ServiceClient get_relative_pose_client_;
00064 iri_laser_icp::GetRelativePose get_relative_pose_srv_;
00065
00066
00067
00068
00069
00070
00071 std::vector<sensor_msgs::LaserScan> laser_scan_buffer_;
00072 std::vector<sensor_msgs::LaserScan> discarded_laser_scan_buffer_;
00073
00074 bool online_mode;
00075 double bad_cov_thres, ICP_covariance_correction_factor;
00076 Vector3d d_base_2_laser;
00077
00078 public:
00085 Scans2OdomAlgNode(void);
00086
00093 ~Scans2OdomAlgNode(void);
00094
00095 protected:
00108 void mainNodeThread(void);
00109
00122 void node_config_update(Config &config, uint32_t level);
00123
00130 void addNodeDiagnostics(void);
00131
00141 Matrix3d rotation_matrix(const double &alpha) const;
00142
00150 Matrix3d covariance_2_matrix(const geometry_msgs::PoseWithCovariance &pose) const;
00151
00159 Vector3d pose_2_vector(const geometry_msgs::Pose &pose) const;
00160
00170 geometry_msgs::PoseWithCovariance eigen_2_posewithcovariance(const Vector3d &p, const Matrix3d &cov) const;
00171
00179 void change_2_base_footprint_frame(Vector3d &odom_ICP, Matrix3d &odom_ICP_cov);
00180
00181
00182
00183
00184 };
00185
00186 #endif