common.h 2.5 KB

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