pilot_apollo_bridge.cc 7.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243
  1. #include "modules/adc/pilot_apollo_bridge/proto/gpsimu.pb.h"
  2. #include "cyber/cyber.h"
  3. #include "cyber/time/rate.h"
  4. #include "cyber/time/time.h"
  5. #include "modules/common/adapters/adapter_gflags.h"
  6. #include "modules/common_msgs/localization_msgs/gps.pb.h"
  7. #include "modules/common_msgs/sensor_msgs/ins.pb.h"
  8. #include "modules/common_msgs/localization_msgs/imu.pb.h"
  9. //car数据定义的引用,可以看出其定义来源于一个proto
  10. // using apollo::communication::proto::Car;
  11. using ::apollo::localization::Gps;
  12. #include <iostream>
  13. #include <chrono>
  14. #include <qglobal.h>
  15. #include "modulecomm.h"
  16. ::apollo::drivers::gnss::Ins ins_;
  17. ::apollo::drivers::gnss::InsStat ins_stat_;
  18. constexpr double DEG_TO_RAD = M_PI / 180.0;
  19. constexpr float FLOAT_NAN = std::numeric_limits<float>::quiet_NaN();
  20. constexpr double azimuth_deg_to_yaw_rad(double azimuth) {
  21. return (90.0 - azimuth) * DEG_TO_RAD;
  22. }
  23. // File expires on: December 2017
  24. // There's two concept about 'time'.
  25. // 1. Unix time : It counts seconds since Jan 1,1970.
  26. // Unix time doesn't include the leap seconds.
  27. //
  28. // 2. GPS time : It counts seconds since Jan 6,1980.
  29. // GPS time does include the leap seconds.
  30. //
  31. // Leap seconds was added in every a few years, See details:
  32. // http://tycho.usno.navy.mil/leapsec.html
  33. // https://en.wikipedia.org/wiki/Leap_second
  34. //
  35. /* leap_seconds table since 1980.
  36. +======+========+========+======+========+========+
  37. | Year | Jun 30 | Dec 31 | Year | Jun 30 | Dec 31 |
  38. +======+========+========+======+========+========+
  39. | 1980 | (already +19) | 1994 | +1 | 0 |
  40. +------+--------+--------+------+--------+--------+
  41. | 1981 | +1 | 0 | 1995 | 0 | +1 |
  42. +------+--------+--------+------+--------+--------+
  43. | 1982 | +1 | 0 | 1997 | +1 | 0 |
  44. +------+--------+--------+------+--------+--------+
  45. | 1983 | +1 | 0 | 1998 | 0 | +1 |
  46. +------+--------+--------+------+--------+--------+
  47. | 1985 | +1 | 0 | 2005 | 0 | +1 |
  48. +------+--------+--------+------+--------+--------+
  49. | 1987 | 0 | +1 | 2008 | 0 | +1 |
  50. +------+--------+--------+------+--------+--------+
  51. | 1989 | 0 | +1 | 2012 | +1 | 0 |
  52. +------+--------+--------+------+--------+--------+
  53. | 1990 | 0 | +1 | 2015 | +1 | 0 |
  54. +------+--------+--------+------+--------+--------+
  55. | 1992 | +1 | 0 | 2016 | 0 | +1 |
  56. +------+--------+--------+------+--------+--------+
  57. | 1993 | +1 | 0 | 2017 | 0 | 0 |
  58. +------+--------+--------+------+--------+--------+
  59. Current TAI - UTC = 37. (mean that: 2017 - 1970/01/01 = 37 seconds)
  60. */
  61. // We build a lookup table to describe relationship that between UTC and
  62. // Leap_seconds.
  63. //
  64. // Column1: UTC time diff (second).
  65. // Shell Example:
  66. // date +%s -d"Jan 1, 2017 00:00:00"
  67. // return 1483257600.
  68. //
  69. // date +%s -d"Jan 1, 1970 00:00:00"
  70. // return 28800.
  71. //
  72. // The diff between 1970/01/01 and 2017/01/01 is 1483228800.
  73. // (1483257600-28800)
  74. //
  75. // Column2: Leap seconds diff with GPS basetime(Jan 6,1980).
  76. // We Know that The leap_seconds have been already added 37 seconds
  77. // util now(2017).
  78. // So we can calculate leap_seconds diff between GPS (from Jan 6,1980)
  79. // and UTC time.
  80. // calc with the formula.
  81. static const int32_t LEAP_SECONDS[][2] = {
  82. {1483228800, 18}, // 2017/01/01
  83. {1435708800, 17}, // 2015/07/01
  84. {1341100800, 16}, // 2012/07/01
  85. {1230768000, 15}, // 2009/01/01
  86. {1136073600, 14}, // 2006/01/01
  87. {915148800, 13}, // 1999/01/01
  88. {867711600, 12}, // 1997/07/01
  89. {820480320, 11}, // 1996/01/01 ;)
  90. //....
  91. //..
  92. // etc.
  93. };
  94. // seconds that UNIX time afront of GPS, without leap seconds.
  95. // Shell:
  96. // time1 = date +%s -d"Jan 6, 1980 00:00:00"
  97. // time2 = date +%s -d"Jan 1, 1970 00:00:00"
  98. // dif_tick = time1-time2
  99. // 315964800 = 315993600 - 28800
  100. const int32_t GPS_AND_SYSTEM_DIFF_SECONDS = 315964800;
  101. template <class T, size_t N>
  102. constexpr size_t array_size(T (&)[N]) {
  103. return N;
  104. }
  105. template <typename T>
  106. T unix2gps(const T unix_seconds) {
  107. for (size_t i = 0; i < array_size(LEAP_SECONDS); ++i) {
  108. if (unix_seconds >= LEAP_SECONDS[i][0]) {
  109. return unix_seconds - (GPS_AND_SYSTEM_DIFF_SECONDS - LEAP_SECONDS[i][1]);
  110. }
  111. }
  112. return static_cast<T>(0);
  113. }
  114. template <typename T>
  115. T gps2unix(const T gps_seconds) {
  116. for (size_t i = 0; i < array_size(LEAP_SECONDS); ++i) {
  117. T result = gps_seconds + (GPS_AND_SYSTEM_DIFF_SECONDS - LEAP_SECONDS[i][1]);
  118. if (result >= LEAP_SECONDS[i][0]) {
  119. return result;
  120. }
  121. }
  122. return static_cast<T>(0);
  123. }
  124. enum class InsStatus : uint32_t {
  125. INACTIVE = 0,
  126. ALIGNING,
  127. HIGH_VARIANCE,
  128. SOLUTION_GOOD,
  129. SOLUTION_FREE = 6,
  130. ALIGNMENT_COMPLETE,
  131. DETERMINING_ORIENTATION,
  132. WAITING_INITIAL_POS,
  133. NONE = std::numeric_limits<uint32_t>::max(),
  134. };
  135. void ListenGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
  136. {
  137. (void)index;
  138. (void)dt;
  139. (void)strmemname;
  140. iv::gps::gpsimu xgpsimu;
  141. if(!xgpsimu.ParseFromArray(strdata,nSize))
  142. {
  143. std::cout<<"ListenRaw Parse error."<<std::endl;
  144. return;
  145. }
  146. int64_t timenow = std::chrono::system_clock::now().time_since_epoch().count();
  147. double seconds = timenow * 1e-9;//gps_week * SECONDS_PER_WEEK + gps_millisecs * 1e-3;
  148. ins_.mutable_position()->set_lon(xgpsimu.lon());
  149. ins_.mutable_position()->set_lat(xgpsimu.lat());
  150. ins_.mutable_position()->set_height(xgpsimu.height());
  151. ins_.mutable_euler_angles()->set_x(xgpsimu.roll() * DEG_TO_RAD);
  152. ins_.mutable_euler_angles()->set_y(-xgpsimu.pitch() * DEG_TO_RAD);
  153. ins_.mutable_euler_angles()->set_z(azimuth_deg_to_yaw_rad(xgpsimu.heading()));
  154. ins_.mutable_linear_velocity()->set_x(xgpsimu.ve());
  155. ins_.mutable_linear_velocity()->set_y(xgpsimu.vn());
  156. ins_.mutable_linear_velocity()->set_z(xgpsimu.vd());
  157. ins_.set_type(apollo::drivers::gnss::Ins::GOOD);
  158. // ins_.set_measurement_time(seconds);
  159. ins_.set_measurement_time(unix2gps(seconds));
  160. ins_.mutable_header()->set_timestamp_sec(apollo::cyber::Time::Now().ToSecond());
  161. double unix_sec = seconds;//apollo::drivers::util::gps2unix(seconds);
  162. ins_stat_.mutable_header()->set_timestamp_sec(unix_sec);
  163. ins_stat_.set_ins_status(3);
  164. ins_stat_.set_pos_type(xgpsimu.rtk_state());
  165. }
  166. void InitIns(){
  167. ins_.mutable_position_covariance()->Resize(9, FLOAT_NAN);
  168. ins_.mutable_euler_angles_covariance()->Resize(9, FLOAT_NAN);
  169. ins_.mutable_linear_velocity_covariance()->Resize(9, FLOAT_NAN);
  170. }
  171. int main(int argc, char *argv[]) {
  172. // 初始化一个cyber框架
  173. apollo::cyber::Init(argv[0]);
  174. // 创建talker节点
  175. auto talker_node = apollo::cyber::CreateNode("pilot_apollo_bridge");
  176. InitIns();
  177. void * paraw = iv::modulecomm::RegisterRecv("hcp2_gpsimu",ListenGPSIMU);
  178. (void)paraw;
  179. std::shared_ptr<apollo::cyber::Writer<apollo::localization::Gps>>
  180. gps_writer_ = talker_node->CreateWriter<Gps>("gps");
  181. std::shared_ptr<apollo::cyber::Writer<InsStatus>> insstatus_writer_ = talker_node->CreateWriter<InsStatus>(FLAGS_ins_status_topic);
  182. std::shared_ptr<apollo::cyber::Writer<apollo::localization::CorrectedImu>> corrimu_writer_ = talker_node->CreateWriter<apollo::localization::CorrectedImu>(FLAGS_imu_topic);
  183. // 从节点创建一个Topic,来实现对车速的查看
  184. // auto talker = talker_node->CreateWriter<Car>("car_speed");
  185. // AINFO << "I'll start telling you the current speed of the car.";
  186. std::cout<<" enter talker."<<std::endl;
  187. //设置初始速度为0,然后速度每秒增加5km/h
  188. uint64_t speed = 0;
  189. while (apollo::cyber::OK()) {
  190. // auto msg = std::make_shared<Car>();
  191. // msg->set_speed(speed);
  192. //假设车速持续增加
  193. speed += 5;
  194. // talker->Write(msg);
  195. sleep(1);
  196. }
  197. return 0;
  198. }