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 _sensors_2_link_alg_node_h_
00026 #define _sensors_2_link_alg_node_h_
00027
00028 #include <Eigen/Dense>
00029
00030 #include <iri_base_algorithm/iri_base_algorithm.h>
00031 #include "sensors_2_link_alg.h"
00032 #include <tf/transform_datatypes.h>
00033
00034
00035 #include <sensor_msgs/LaserScan.h>
00036 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <nav_msgs/Odometry.h>
00039
00040
00041 #include <iri_poseslam/GetLink.h>
00042 #include <iri_laser_icp/GetRelativePose.h>
00043
00044
00045
00046 using namespace Eigen;
00047
00052 class Sensors2LinkAlgNode : public algorithm_base::IriBaseAlgorithm<Sensors2LinkAlgorithm>
00053 {
00054 private:
00055
00056
00057
00058 ros::Subscriber scan_subscriber_;
00059 void scan_callback(const sensor_msgs::LaserScan::ConstPtr& msg);
00060
00061 ros::Subscriber odom_relative_subscriber_;
00062 void odom_relative_callback(const nav_msgs::Odometry::ConstPtr& msg);
00063
00064 ros::Subscriber cmd_vel_subscriber_;
00065 void cmd_vel_callback(const geometry_msgs::Twist::ConstPtr& msg);
00066
00067
00068 ros::ServiceServer get_link_server_;
00069 bool get_linkCallback(iri_poseslam::GetLink::Request &req, iri_poseslam::GetLink::Response &res);
00070
00071
00072 ros::ServiceClient get_relative_pose_client_;
00073 iri_laser_icp::GetRelativePose get_relative_pose_srv_;
00074
00075
00076
00077
00078
00079
00080
00081 sensor_msgs::LaserScan last_laser_scan_, ready_laser_scan_;
00082
00083 bool new_laser_scan_, fusion_ready_;
00084 uint ready_odom_id_, prev_seq;
00085
00086 Vector3d odom_rel_, d_local;
00087 Matrix3d odom_rel_cov_, Jp, Jd, Q;
00088 ros::Time odom_rel_time_;
00089
00090 std::vector<geometry_msgs::PoseWithCovarianceStamped> odom_buffer_;
00091 std::vector<sensor_msgs::LaserScan> laser_scan_buffer_;
00092 std::vector<Vector3d> odom_rel_buffer_;
00093 std::vector<Matrix3d> odom_rel_cov_buffer_;
00094 std::vector<ros::Time> odom_rel_time_buffer_;
00095
00096 bool online_mode, stopped_since_last_odom, currently_stopped;
00097 double ICP_covariance_correction_factor;
00098 Vector3d d_base_2_laser;
00099
00100 public:
00107 Sensors2LinkAlgNode(void);
00108
00115 ~Sensors2LinkAlgNode(void);
00116
00117 protected:
00130 void mainNodeThread(void);
00131
00144 void node_config_update(Config &config, uint32_t level);
00145
00152 void addNodeDiagnostics(void);
00153
00161 geometry_msgs::PoseWithCovarianceStamped odometry_fusion(const sensor_msgs::LaserScan &laser_scan, const int &odom_rel_idx);
00162
00172 Matrix3d rotation_matrix(const double &alpha) const;
00173
00181 Matrix3d covariance_2_matrix(const geometry_msgs::PoseWithCovariance &pose) const;
00182
00190 Vector3d pose_2_vector(const geometry_msgs::Pose &pose) const;
00191
00201 geometry_msgs::PoseWithCovariance eigen_2_posewithcovariance(const Vector3d &p, const Matrix3d &cov) const;
00202
00212 geometry_msgs::Pose vector_2_pose(const Vector3d &p) const;
00213
00220 iri_poseslam::GetLink::Response offline_odometry();
00221
00228 iri_poseslam::GetLink::Response online_odometry();
00229
00238 std::pair<Vector3d, Matrix3d> interpolate_odom_rel(const int &odom_rel_idx, const ros::Time scan_stamp);
00239
00246 void base_2_laser_frame(Vector3d &prior_d);
00247
00255 void laser_2_base_frame(Vector3d &odom_ICP, Matrix3d &odom_ICP_cov);
00256
00257
00258
00259 };
00260
00261 #endif