common.h 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  1. #ifndef COMMON_H
  2. #define COMMON_H
  3. #include <ros/ros.h>
  4. #include <sensor_msgs/PointCloud2.h>
  5. #include <sensor_msgs/Imu.h>
  6. #include <nav_msgs/Path.h>
  7. #include <nav_msgs/Odometry.h>
  8. #include <visualization_msgs/Marker.h>
  9. #include <eigen_conversions/eigen_msg.h>
  10. #include <message_filters/subscriber.h>
  11. #include <geometry_msgs/Vector3Stamped.h>
  12. #include <geometry_msgs/QuaternionStamped.h>
  13. #include <sensor_msgs/NavSatFix.h>
  14. #include <tf/LinearMath/Quaternion.h>
  15. #include <tf/transform_listener.h>
  16. #include <tf/transform_datatypes.h>
  17. #include <tf/transform_broadcaster.h>
  18. #include <pcl/point_cloud.h>
  19. #include <pcl/point_types.h>
  20. #include <pcl_ros/point_cloud.h>
  21. #include <pcl_conversions/pcl_conversions.h>
  22. #include <pcl/filters/filter.h>
  23. #include <pcl/filters/voxel_grid.h>
  24. #include <pcl/kdtree/kdtree_flann.h>
  25. #include <pcl/common/common.h>
  26. #include <pcl/pcl_macros.h>
  27. #include <pcl/range_image/range_image.h>
  28. #include <pcl/registration/icp.h>
  29. #include <cmath>
  30. #include <ctime>
  31. #include <array>
  32. #include <string>
  33. #include <vector>
  34. #include <algorithm>
  35. #include <iostream>
  36. #include <fstream>
  37. #include <thread>
  38. #include <mutex>
  39. #include <queue>
  40. #include <assert.h>
  41. #include <Eigen/Dense>
  42. using namespace std;
  43. struct PointPoseInfo
  44. {
  45. double x;
  46. double y;
  47. double z;
  48. double qw;
  49. double qx;
  50. double qy;
  51. double qz;
  52. int idx;
  53. double time;
  54. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  55. } EIGEN_ALIGN16;
  56. POINT_CLOUD_REGISTER_POINT_STRUCT (PointPoseInfo,
  57. (double, x, x) (double, y, y) (double, z, z)
  58. (double, qw, qw) (double, qx, qx) (double, qy, qy) (double, qz, qz)
  59. (int, idx, idx) (double, time, time)
  60. )
  61. // PCL point types
  62. using pcl::PointXYZI;
  63. using pcl::PointXYZINormal;
  64. typedef pcl::PointXYZINormal PointType;
  65. // Get parameters from yaml file
  66. template <class class_name>
  67. bool getParameter(const std::string& paramName, class_name& param)
  68. {
  69. std::string nodeName = ros::this_node::getName();
  70. std::string paramKey;
  71. if (!ros::param::search(paramName, paramKey))
  72. {
  73. ROS_ERROR("%s: Failed to search for parameter '%s'.", nodeName.c_str(), paramName.c_str());
  74. return false;
  75. }
  76. if (!ros::param::has(paramKey))
  77. {
  78. ROS_ERROR("%s: Missing required parameter '%s'.", nodeName.c_str(), paramName.c_str());
  79. return false;
  80. }
  81. if (!ros::param::get(paramKey, param))
  82. {
  83. ROS_ERROR("%s: Failed to get parameter '%s'.", nodeName.c_str(), paramName.c_str());
  84. return false;
  85. }
  86. return true;
  87. }
  88. #endif // COMMON_H