rslidar_config.hpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159
  1. #ifndef RSLIDAR_JSON_CONFIG_H_
  2. #define RSLIDAR_JSON_CONFIG_H_
  3. #include <vector>
  4. #include "json/json.h"
  5. #include "rs_driver/driver/driver_param.hpp"
  6. class RsliadrJsonConfig {
  7. public:
  8. RsliadrJsonConfig(std::string &config_path) {
  9. m_config_path_ = config_path;
  10. m_config_.resize(0);
  11. }
  12. ~RsliadrJsonConfig() {};
  13. bool getRSDriverParam(robosense::lidar::RSDriverParam &param, int id) {
  14. int sn = getSN(id);
  15. if (sn == -1) {
  16. LOG(INFO) << id << " false";
  17. return false;
  18. }
  19. // TODO json校验
  20. param.lidar_type = strToLidarType(m_config_["etc"][sn]["lidar_type"].asString());
  21. param.input_type = strToInputType(m_config_["etc"][sn]["input_type"].asString());
  22. param.input_param.msop_port = id;
  23. param.input_param.difop_port = m_config_["etc"][sn]["input_param"]["difop_port"].asUInt();
  24. param.input_param.host_address = m_config_["etc"][sn]["input_param"]["host_address"].asString();
  25. param.input_param.group_address = m_config_["etc"][sn]["input_param"]["group_address"].asString();
  26. param.input_param.pcap_path = m_config_["etc"][sn]["input_param"]["pcap_path"].asString();
  27. param.input_param.pcap_rate = m_config_["etc"][sn]["input_param"]["pcap_rate"].asFloat();
  28. param.input_param.pcap_repeat = m_config_["etc"][sn]["input_param"]["pcap_repeat"].asBool();
  29. param.input_param.use_vlan = m_config_["etc"][sn]["input_param"]["use_vlan"].asBool();
  30. param.input_param.user_layer_bytes = m_config_["etc"][sn]["input_param"]["user_layer_bytes"].asUInt();
  31. param.input_param.tail_layer_bytes = m_config_["etc"][sn]["input_param"]["tail_layer_bytes"].asUInt();
  32. param.decoder_param.wait_for_difop = m_config_["etc"][sn]["decoder_param"]["wait_for_difop"].asBool();
  33. param.decoder_param.min_distance = m_config_["etc"][sn]["decoder_param"]["min_distance"].asFloat();
  34. param.decoder_param.max_distance = m_config_["etc"][sn]["decoder_param"]["max_distance"].asFloat();
  35. float value = m_config_["etc"][sn]["decoder_param"]["start_angle"].asFloat();
  36. if (value < 0 ) {
  37. value += 360;
  38. } else if (value > 360) {
  39. value -= 360;
  40. }
  41. param.decoder_param.start_angle = value;
  42. value = m_config_["etc"][sn]["decoder_param"]["end_angle"].asFloat();
  43. if (value < 0 ) {
  44. value += 360;
  45. } else if (value > 360) {
  46. value -= 360;
  47. }
  48. param.decoder_param.end_angle = value;
  49. param.decoder_param.use_lidar_clock = m_config_["etc"][sn]["decoder_param"]["use_lidar_clock"].asBool();
  50. param.decoder_param.dense_points = m_config_["etc"][sn]["decoder_param"]["dense_points"].asBool();
  51. param.decoder_param.config_from_file = m_config_["etc"][sn]["decoder_param"]["config_from_file"].asBool();
  52. param.decoder_param.angle_path = m_config_["etc"][sn]["decoder_param"]["angle_path"].asString();
  53. param.decoder_param.split_frame_mode = (SplitFrameMode) m_config_["etc"][sn]["decoder_param"]["split_frame_mode"].asInt();
  54. param.decoder_param.split_angle = m_config_["etc"][sn]["decoder_param"]["split_angle"].asFloat();
  55. param.decoder_param.num_blks_split = m_config_["etc"][sn]["decoder_param"]["num_blks_split"].asUInt();
  56. getRSTransformParam(param.decoder_param.transform_param, sn);
  57. return true;
  58. }
  59. bool getRSTransformParam(robosense::lidar::RSTransformParam &param, int id) {
  60. int sn = getSN(id);
  61. if (sn == -1) {
  62. return false;
  63. }
  64. param.x = m_config_["etc"][sn]["transform"]["x"].asFloat();
  65. param.y = m_config_["etc"][sn]["transform"]["y"].asFloat();
  66. param.z = m_config_["etc"][sn]["transform"]["z"].asFloat();
  67. param.roll = m_config_["etc"][sn]["transform"]["roll"].asFloat();
  68. param.pitch = m_config_["etc"][sn]["transform"]["pitch"].asFloat();
  69. param.yaw = m_config_["etc"][sn]["transform"]["yaw"].asFloat();
  70. return true;
  71. }
  72. bool getMatrix4dParam(Eigen::Matrix4d &param, int id) {
  73. int sn = getSN(id);
  74. if (sn == -1) {
  75. return false;
  76. }
  77. float r, p, y, cx, cy, cz;
  78. r = m_config_["etc"][sn]["calib"]["r"].asFloat();
  79. p = m_config_["etc"][sn]["calib"]["p"].asFloat();
  80. y = m_config_["etc"][sn]["calib"]["y"].asFloat();
  81. cx = m_config_["etc"][sn]["calib"]["cx"].asFloat();
  82. cy = m_config_["etc"][sn]["calib"]["cy"].asFloat();
  83. cz = m_config_["etc"][sn]["calib"]["cz"].asFloat();
  84. Eigen::AngleAxisd rot_x = Eigen::AngleAxisd(r * M_PI / 180.0, Eigen::Vector3d::UnitX());
  85. Eigen::AngleAxisd rot_y = Eigen::AngleAxisd(p * M_PI / 180.0, Eigen::Vector3d::UnitY());
  86. Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(y * M_PI / 180.0, Eigen::Vector3d::UnitZ());
  87. Eigen::Vector3d trans(cx, cy, cz);
  88. param << rot_x.toRotationMatrix() * rot_y.toRotationMatrix() *
  89. rot_z.toRotationMatrix(), trans, 0.0, 0.0, 0.0, 1.0;
  90. return true;
  91. }
  92. bool getLidarIdList(std::vector<int> &list) {
  93. if (!ReadJsonFile(m_config_path_, m_config_)) {
  94. return false;
  95. }
  96. if (!m_config_.isMember("etc") || !m_config_["etc"].isArray()) {
  97. return false;
  98. }
  99. for (int i = 0; i < m_config_["etc"].size(); i++) {
  100. if (!m_config_["etc"][i]["enable"].asBool()) {
  101. continue;
  102. }
  103. list.emplace_back(m_config_["etc"][i]["input_param"]["msop_port"].asUInt());
  104. }
  105. return true;
  106. }
  107. bool setConfigPath(std::string path) {
  108. m_config_path_ = path;
  109. m_config_.resize(0);
  110. return ReadJsonFile(m_config_path_, m_config_);
  111. }
  112. private:
  113. int getSN(const int &id) {
  114. if (!ReadJsonFile(m_config_path_, m_config_)) {
  115. return -1;
  116. }
  117. if (!m_config_.isMember("etc") || !m_config_["etc"].isArray()) {
  118. return -1;
  119. }
  120. for (int i = 0; i < m_config_["etc"].size(); i++) {
  121. if(m_config_["etc"][i]["input_param"]["msop_port"].asUInt() == id) {
  122. if (!m_config_["etc"][i]["enable"].asBool()) {
  123. return -1;
  124. }
  125. return i;
  126. }
  127. }
  128. return -1;
  129. }
  130. private:
  131. Json::Value m_config_;
  132. std::string m_config_path_;
  133. };
  134. #endif