Apollo 10.0
自动驾驶开放平台
apollo::localization::msf::MeasureRepublishProcess类 参考

process lidar msg for localization 更多...

#include <measure_republish_process.h>

apollo::localization::msf::MeasureRepublishProcess 的协作图:

Public 类型

typedef drivers::gnss::GnssBestPose GnssBestPose
 

Public 成员函数

 MeasureRepublishProcess ()
 
 ~MeasureRepublishProcess ()
 
common::Status Init (const LocalizationIntegParam &params)
 
bool NovatelBestgnssposProcess (const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
 
void GnssLocalProcess (const MeasureData &gnss_local_msg, MeasureData *measure)
 
void IntegPvaProcess (const InsPva &inspva_msg)
 
bool LidarLocalProcess (const LocalizationEstimate &lidar_local_msg, MeasureData *measure)
 
bool GnssHeadingProcess (const drivers::gnss::Heading &heading_msg, MeasureData *measure, int *status)
 

Protected 成员函数

bool IsSinsAlign ()
 
bool CheckBestgnssposeStatus (const GnssBestPose &bestgnsspos_msg)
 
bool CheckBestgnssPoseXYStd (const GnssBestPose &bestgnsspos_msg)
 
void TransferXYZFromBestgnsspose (const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
 
void TransferFirstMeasureFromBestgnsspose (const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
 
bool CalculateVelFromBestgnsspose (const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
 
bool LoadImuGnssAntennaExtrinsic (std::string file_path, VehicleGnssAntExtrinsic *extrinsic) const
 

详细描述

process lidar msg for localization

在文件 measure_republish_process.h62 行定义.

成员类型定义说明

◆ GnssBestPose

构造及析构函数说明

◆ MeasureRepublishProcess()

apollo::localization::msf::MeasureRepublishProcess::MeasureRepublishProcess ( )

在文件 measure_republish_process.cc36 行定义.

37 : pre_bestgnsspose_(),
38 pre_bestgnsspose_valid_(false),
39 send_init_bestgnsspose_(false),
40 pva_buffer_size_(150),
41 local_utm_zone_id_(50),
42 is_trans_gpstime_to_utctime_(true),
43 map_height_time_(0.0),
44 gnss_mode_(GnssMode::NOVATEL) {}

◆ ~MeasureRepublishProcess()

apollo::localization::msf::MeasureRepublishProcess::~MeasureRepublishProcess ( )

在文件 measure_republish_process.cc46 行定义.

46{}

成员函数说明

◆ CalculateVelFromBestgnsspose()

bool apollo::localization::msf::MeasureRepublishProcess::CalculateVelFromBestgnsspose ( const GnssBestPose bestgnsspos_msg,
MeasureData *  measure 
)
protected

在文件 measure_republish_process.cc451 行定义.

452 {
453 CHECK_NOTNULL(measure);
454
455 TransferXYZFromBestgnsspose(bestgnsspos_msg, measure);
456
457 measure->measure_type = MeasureType::GNSS_POS_VEL;
458 measure->frame_type = FrameType::ENU;
459 measure->is_have_variance = false;
460
461 if (!pre_bestgnsspose_valid_) {
462 pre_bestgnsspose_valid_ = true;
463 pre_bestgnsspose_ = *measure;
464 return false;
465 }
466
467 static int position_good_counter = 0;
468 if (position_good_counter < BESTPOSE_GOOD_COUNT) {
469 ++position_good_counter;
470 pre_bestgnsspose_ = *measure;
471 return false;
472 }
473
474 const double re = 6378137.0;
475 const double e = 0.0033528;
476 double temp_sin_lati_2 =
477 sin(measure->gnss_pos.latitude) * sin(measure->gnss_pos.latitude);
478 double rn = re / (1 - e * temp_sin_lati_2);
479 double rm = re / (1 + 2.0 * e - 3.0 * e * temp_sin_lati_2);
480
481 double inv_time = 1.0 / (measure->time - pre_bestgnsspose_.time);
482 if (measure->time - pre_bestgnsspose_.time > BESTPOSE_TIME_MAX_INTERVAL) {
483 pre_bestgnsspose_ = *measure;
484 position_good_counter = 0;
485 return false;
486 }
487 measure->gnss_vel.ve =
488 (measure->gnss_pos.longitude - pre_bestgnsspose_.gnss_pos.longitude) *
489 rn * inv_time * cos(measure->gnss_pos.latitude);
490 measure->gnss_vel.vn =
491 (measure->gnss_pos.latitude - pre_bestgnsspose_.gnss_pos.latitude) * rm *
492 inv_time;
493 measure->gnss_vel.vu =
494 (measure->gnss_pos.height - pre_bestgnsspose_.gnss_pos.height) * inv_time;
495
496 pre_bestgnsspose_ = *measure;
497 AINFO << "novatel bestgnsspos velocity: " << measure->gnss_vel.ve << " "
498 << measure->gnss_vel.vn << " " << measure->gnss_vel.vu;
499
500 static double pre_yaw_from_vel = 0.0;
501 double yaw_from_vel = atan2(measure->gnss_vel.ve, measure->gnss_vel.vn);
502 if (!pre_yaw_from_vel) {
503 pre_yaw_from_vel = yaw_from_vel;
504 return false;
505 } else {
506 static constexpr double rad_round = 2 * M_PI;
507 static constexpr double rad_pi = M_PI;
508
509 double delta_yaw = yaw_from_vel - pre_yaw_from_vel;
510 if (delta_yaw > rad_pi) {
511 delta_yaw = delta_yaw - rad_round;
512 }
513 if (delta_yaw < -rad_pi) {
514 delta_yaw = delta_yaw + rad_round;
515 }
516
517 AINFO << "yaw calculated from position difference: "
518 << yaw_from_vel * RAD_TO_DEG;
519 static constexpr double rad_5deg = 5 * DEG_TO_RAD;
520 if (delta_yaw > rad_5deg || delta_yaw < -rad_5deg) {
521 AWARN << "novatel bestgnsspos delta yaw is large! "
522 << "pre, cur yaw from vel and delta: "
523 << pre_yaw_from_vel * RAD_TO_DEG << " " << yaw_from_vel * RAD_TO_DEG
524 << " " << delta_yaw * RAD_TO_DEG;
525 pre_yaw_from_vel = yaw_from_vel;
526 return false;
527 }
528 pre_yaw_from_vel = yaw_from_vel;
529 }
530
531 return true;
532}
void TransferXYZFromBestgnsspose(const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
#define DEG_TO_RAD
#define RAD_TO_DEG
float cos(Angle16 a)
Definition angle.cc:42
float sin(Angle16 a)
Definition angle.cc:25

◆ CheckBestgnssposeStatus()

bool apollo::localization::msf::MeasureRepublishProcess::CheckBestgnssposeStatus ( const GnssBestPose bestgnsspos_msg)
protected

在文件 measure_republish_process.cc702 行定义.

703 {
704 int gnss_solution_status = static_cast<int>(bestgnsspos_msg.sol_status());
705 int gnss_position_type = static_cast<int>(bestgnsspos_msg.sol_type());
706 AINFO << "the gnss solution_status and position_type: "
707 << gnss_solution_status << " " << gnss_position_type;
708
709 if (gnss_solution_status != 0) {
710 AINFO << "novatel gnsspos's solution_status is not computed: "
711 << gnss_solution_status;
712 return false;
713 }
714 if (gnss_position_type == 0 || gnss_position_type == 1 ||
715 gnss_position_type == 2) {
716 AINFO << "novatel gnsspos's solution_type is invalid "
717 << "or xy fixed or height fixed: " << gnss_position_type;
718 return false;
719 }
720
721 return true;
722}

◆ CheckBestgnssPoseXYStd()

bool apollo::localization::msf::MeasureRepublishProcess::CheckBestgnssPoseXYStd ( const GnssBestPose bestgnsspos_msg)
protected

在文件 measure_republish_process.cc689 行定义.

690 {
691 // check the standard deviation of xy
692 if ((bestgnsspos_msg.longitude_std_dev() > GNSS_XY_STD_THRESHOLD) ||
693 (bestgnsspos_msg.latitude_std_dev() > GNSS_XY_STD_THRESHOLD)) {
694 AWARN << "the position std is large: "
695 << bestgnsspos_msg.longitude_std_dev() << " "
696 << bestgnsspos_msg.latitude_std_dev();
697 return false;
698 }
699 return true;
700}

◆ GnssHeadingProcess()

bool apollo::localization::msf::MeasureRepublishProcess::GnssHeadingProcess ( const drivers::gnss::Heading heading_msg,
MeasureData *  measure,
int *  status 
)

在文件 measure_republish_process.cc534 行定义.

536 {
537 if ((imu_gnssant_extrinsic_.ant_num == 1)) {
538 return false;
539 }
540 int solution_status = heading_msg.solution_status();
541 int position_type = heading_msg.position_type();
542 AINFO << "the heading solution_status and position_type: " << solution_status
543 << " " << position_type;
544
545 if (solution_status != 0) {
546 *status = 93;
547 AINFO << "the heading's solution_status is not computed: "
548 << solution_status;
549 return false;
550 }
551 *status = position_type;
552 if ((position_type == 0) || (position_type == 1)) {
553 AINFO << "the heading's solution_type is invalid or fixed: "
554 << position_type;
555 return false;
556 }
557 measure_data->time = heading_msg.measurement_time();
558 if (is_trans_gpstime_to_utctime_) {
559 measure_data->time = GpsToUnixSeconds(measure_data->time);
560 }
561
562 novatel_heading_mutex_.lock();
563 novatel_heading_time_ = measure_data->time;
564 novatel_heading_mutex_.unlock();
565
566 double delta_time_between_height = 0.0;
567 height_mutex_.lock();
568 delta_time_between_height = measure_data->time - map_height_time_;
569 height_mutex_.unlock();
570
571 if (delta_time_between_height < 1.0) {
572 AINFO << "the heading time and delta time: " << std::setprecision(15)
573 << measure_data->time << " " << delta_time_between_height;
574 return false;
575 }
576
577 integ_pva_mutex_.lock();
578 bool is_sins_align =
579 integ_pva_list_.back().init_and_alignment && (integ_pva_list_.size() > 1);
580 integ_pva_mutex_.unlock();
581
582 if (is_sins_align) {
583 static double pre_publish_time = 0.0;
584 if (measure_data->time - pre_publish_time < 0.5) {
585 return false;
586 }
587 pre_publish_time = measure_data->time;
588 }
589 double gnss_yaw = heading_msg.heading();
590 double heading_std = heading_msg.heading_std_dev();
591
592 static double imu_ant_yaw_angle = 0.0;
593 if (imu_ant_yaw_angle == 0.0) {
594 imu_ant_yaw_angle =
595 -atan2(imu_gnssant_extrinsic_.transform_2.translation()[0] -
596 imu_gnssant_extrinsic_.transform_1.translation()[0],
597 imu_gnssant_extrinsic_.transform_2.translation()[1] -
598 imu_gnssant_extrinsic_.transform_1.translation()[1]) *
599 57.295779513082323;
600 AINFO << "imu_gnssant_extrinsic_: "
601 << imu_gnssant_extrinsic_.transform_2.translation()[0] << ", "
602 << imu_gnssant_extrinsic_.transform_1.translation()[0] << ", "
603 << imu_gnssant_extrinsic_.transform_2.translation()[1] << ", "
604 << imu_gnssant_extrinsic_.transform_2.translation()[1];
605 AINFO << "the yaw between double ant yaw and vehicle: "
606 << imu_ant_yaw_angle;
607 }
608 AINFO << "novatel heading is: " << std::setprecision(15) << measure_data->time
609 << " " << std::setprecision(6) << gnss_yaw;
610 if (gnss_yaw > 180) {
611 // the novatel yaw angle is 0-360deg
612 gnss_yaw -= 360.0;
613 }
614 gnss_yaw += imu_ant_yaw_angle;
615
616 if (gnss_yaw > 180) {
617 gnss_yaw -= 360.0;
618 }
619 measure_data->measure_type = MeasureType::GNSS_DOUBLE_ANT_YAW;
620 measure_data->is_have_variance = true;
621 // 3.046174197867086e-04 = (pi / 180)^2
622 AINFO << "the novatel heading std: " << std::setprecision(15)
623 << measure_data->time << " " << heading_std;
624 measure_data->variance[8][8] =
625 heading_std * heading_std * 3.046174197867086e-04;
626 measure_data->gnss_att.yaw = -gnss_yaw * 0.017453292519943;
627
628 AINFO << "measure data heading is: " << std::setprecision(15)
629 << measure_data->time << " " << std::setprecision(6)
630 << measure_data->gnss_att.yaw;
631
632 return true;
633}
T GpsToUnixSeconds(T gps_seconds)

◆ GnssLocalProcess()

void apollo::localization::msf::MeasureRepublishProcess::GnssLocalProcess ( const MeasureData &  gnss_local_msg,
MeasureData *  measure 
)

在文件 measure_republish_process.cc184 行定义.

185 {
186 if (gnss_mode_ != GnssMode::SELF) {
187 return;
188 }
189
190 CHECK_NOTNULL(measure);
191
192 MeasureData measure_data = gnss_local_msg;
193 if (is_trans_gpstime_to_utctime_) {
194 measure_data.time = TimeUtil::Gps2Unix(measure_data.time);
195 }
196
197 AINFO << "the gnss velocity: " << measure_data.gnss_vel.ve << " "
198 << measure_data.gnss_vel.vn << " " << measure_data.gnss_vel.vu;
199
200 measure_data.gnss_att.pitch = 0.0;
201 measure_data.gnss_att.roll = 0.0;
202
203 Eigen::Vector3d pos_xyz = Eigen::Vector3d::Zero();
204 pos_xyz[0] = measure_data.gnss_pos.longitude;
205 pos_xyz[1] = measure_data.gnss_pos.latitude;
206 pos_xyz[2] = measure_data.gnss_pos.height;
207
208 Eigen::Vector3d pos_blh = Eigen::Vector3d::Zero();
210 measure_data.gnss_pos.longitude = pos_blh[0];
211 measure_data.gnss_pos.latitude = pos_blh[1];
212 measure_data.gnss_pos.height = pos_blh[2];
213
214 double ve_std = std::sqrt(measure_data.variance[3][3]);
215 double vn_std = std::sqrt(measure_data.variance[4][4]);
216 double vu_std = std::sqrt(measure_data.variance[5][5]);
217 AINFO << "the gnss velocity std: " << ve_std << " " << vn_std << " "
218 << vu_std;
219
220 bool is_sins_align = IsSinsAlign();
221
222 if (is_sins_align) {
223 measure_data.measure_type = MeasureType::GNSS_POS_ONLY;
224 height_mutex_.lock();
225 if ((measure_data.time - 1.0 < map_height_time_)) {
226 measure_data.measure_type = MeasureType::GNSS_POS_XY;
227 }
228 height_mutex_.unlock();
229 measure_data.is_have_variance = true;
230 } else {
231 measure_data.measure_type = MeasureType::GNSS_POS_VEL;
232 measure_data.is_have_variance = false;
233
234 static bool is_sent_init_pos = false;
235 if (!is_sent_init_pos) {
236 is_sent_init_pos = true;
237 measure_data.gnss_vel.ve = 0.0;
238 measure_data.gnss_vel.vn = 0.0;
239 measure_data.gnss_vel.vu = 0.0;
240 AINFO << "send sins init position using rtk-gnss position!";
241 *measure = measure_data;
242 return;
243 }
244
245 static int position_good_counter = 0;
246 if (position_good_counter < 10) {
247 ++position_good_counter;
248 return;
249 }
250
251 if (gnss_local_msg.measure_type != MeasureType::GNSS_POS_VEL &&
252 gnss_local_msg.measure_type != MeasureType::ENU_VEL_ONLY) {
253 AERROR << "gnss does not have velocity,"
254 << "the gnss velocity std: " << ve_std << " " << vn_std << " "
255 << vu_std;
256 return;
257 }
258 if (!gnss_local_msg.is_have_variance) {
259 AERROR << "gnss velocity does not have velocity variance!";
260 return;
261 } else {
262 if ((ve_std > 0.1) || (vn_std > 0.1)) {
263 AWARN << "gnss velocity variance is large: " << ve_std << " " << vn_std;
264 return;
265 }
266 }
267
268 static double pre_yaw_from_vel = 0.0;
269 static double pre_measure_time = 0.0;
270 double yaw_from_vel =
271 atan2(measure_data.gnss_vel.ve, measure_data.gnss_vel.vn);
272 if (pre_measure_time < 0.1) {
273 pre_measure_time = measure_data.time;
274 pre_yaw_from_vel = yaw_from_vel;
275 return;
276 } else {
277 static constexpr double rad_round = 2 * M_PI;
278 static constexpr double rad_pi = M_PI;
279
280 double delta_yaw = yaw_from_vel - pre_yaw_from_vel;
281 if (delta_yaw > rad_pi) {
282 delta_yaw = delta_yaw - rad_round;
283 }
284 if (delta_yaw < -rad_pi) {
285 delta_yaw = delta_yaw + rad_round;
286 }
287
288 AINFO << "yaw from position difference: " << yaw_from_vel * RAD_TO_DEG;
289 double delta_time = measure_data.time - pre_measure_time;
290 if (delta_time < 1.0e-10) {
291 AINFO << "the delta time is too small: " << delta_time;
292 }
293 double yaw_incr = delta_yaw / delta_time;
294 // 0.0872rad = 5deg
295 static constexpr double rad_5deg = 5 * DEG_TO_RAD;
296 if ((yaw_incr > rad_5deg) || (yaw_incr < -rad_5deg)) {
297 AWARN << "yaw velocity is large! pre, "
298 << "cur yaw from vel and velocity: "
299 << pre_yaw_from_vel * RAD_TO_DEG << " "
300 << yaw_from_vel * RAD_TO_DEG << " " << yaw_incr * RAD_TO_DEG;
301 pre_measure_time = measure_data.time;
302 pre_yaw_from_vel = yaw_from_vel;
303 return;
304 }
305 pre_measure_time = measure_data.time;
306 pre_yaw_from_vel = yaw_from_vel;
307 }
308 }
309 *measure = measure_data;
310
311 ADEBUG << std::setprecision(16)
312 << "MeasureDataRepublish Debug Log: rtkgnss msg: "
313 << "[time:" << measure_data.time << "]"
314 << "[x:" << measure_data.gnss_pos.longitude * RAD_TO_DEG << "]"
315 << "[y:" << measure_data.gnss_pos.latitude * RAD_TO_DEG << "]"
316 << "[z:" << measure_data.gnss_pos.height << "]"
317 << "[std_x:" << measure_data.variance[0][0] << "]"
318 << "[std_y:" << measure_data.variance[1][1] << "]"
319 << "[std_z:" << measure_data.variance[2][2] << "]";
320}
static double Gps2Unix(double gps_time)
Definition time_util.h:37
static bool XYZToBlh(const Vector3d &xyz, Vector3d *blh)
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ Init()

Status apollo::localization::msf::MeasureRepublishProcess::Init ( const LocalizationIntegParam params)

在文件 measure_republish_process.cc48 行定义.

48 {
49 local_utm_zone_id_ = params.utm_zone_id;
50 is_trans_gpstime_to_utctime_ = params.is_trans_gpstime_to_utctime;
51 gnss_mode_ = GnssMode(params.gnss_mode);
52
53 pva_buffer_size_ = 150;
54
55 map_height_time_ = 0.0;
56
57 novatel_heading_time_ = 0.0;
58
59 std::ifstream imu_ant_fin(params.ant_imu_leverarm_file.c_str());
60 AINFO << "the ant_imu_leverarm file: " << params.ant_imu_leverarm_file.c_str()
61 << std::endl;
62 if (imu_ant_fin) {
63 bool success = LoadImuGnssAntennaExtrinsic(params.ant_imu_leverarm_file,
64 &imu_gnssant_extrinsic_);
65 if (!success) {
66 AERROR << "IntegratedLocalization: Fail to access the lever arm "
67 "between imu and gnss extrinsic file: "
68 << params.ant_imu_leverarm_file;
69 }
70 AINFO << "gnss and imu lever arm in vehicle frame: "
71 << " " << imu_gnssant_extrinsic_.ant_num << " "
72 << imu_gnssant_extrinsic_.transform_1.translation()[0] << " "
73 << imu_gnssant_extrinsic_.transform_1.translation()[1] << " "
74 << imu_gnssant_extrinsic_.transform_1.translation()[2] << " "
75 << imu_gnssant_extrinsic_.transform_2.translation()[0] << " "
76 << imu_gnssant_extrinsic_.transform_2.translation()[1] << " "
77 << imu_gnssant_extrinsic_.transform_2.translation()[2];
78 } else {
79 AINFO << "the ant_imu_leverarm_file does not existence!";
80 }
81
82 double vehicle_to_imu_quatern[4] = {
83 params.vehicle_to_imu_quatern.w, params.vehicle_to_imu_quatern.x,
84 params.vehicle_to_imu_quatern.y, params.vehicle_to_imu_quatern.z};
85
86 double dcm[3][3] = {0.0};
87 math::QuaternionToDcm(&vehicle_to_imu_quatern[0], dcm);
88 double lever_arm_x = imu_gnssant_extrinsic_.transform_1.translation()[0];
89 double lever_arm_y = imu_gnssant_extrinsic_.transform_1.translation()[1];
90 double lever_arm_z = imu_gnssant_extrinsic_.transform_1.translation()[2];
91
92 imu_gnssant_extrinsic_.transform_1.translation()[0] =
93 dcm[0][0] * lever_arm_x + dcm[0][1] * lever_arm_y +
94 dcm[0][2] * lever_arm_z;
95 imu_gnssant_extrinsic_.transform_1.translation()[1] =
96 dcm[1][0] * lever_arm_x + dcm[1][1] * lever_arm_y +
97 dcm[1][2] * lever_arm_z;
98 imu_gnssant_extrinsic_.transform_1.translation()[2] =
99 dcm[2][0] * lever_arm_x + dcm[2][1] * lever_arm_y +
100 dcm[2][2] * lever_arm_z;
101
102 lever_arm_x = imu_gnssant_extrinsic_.transform_2.translation()[0];
103 lever_arm_y = imu_gnssant_extrinsic_.transform_2.translation()[1];
104 lever_arm_z = imu_gnssant_extrinsic_.transform_2.translation()[2];
105
106 imu_gnssant_extrinsic_.transform_2.translation()[0] =
107 dcm[0][0] * lever_arm_x + dcm[0][1] * lever_arm_y +
108 dcm[0][2] * lever_arm_z;
109 imu_gnssant_extrinsic_.transform_2.translation()[1] =
110 dcm[1][0] * lever_arm_x + dcm[1][1] * lever_arm_y +
111 dcm[1][2] * lever_arm_z;
112 imu_gnssant_extrinsic_.transform_2.translation()[2] =
113 dcm[2][0] * lever_arm_x + dcm[2][1] * lever_arm_y +
114 dcm[2][2] * lever_arm_z;
115
116 AINFO << "gnss and imu lever arm in imu frame: "
117 << " " << imu_gnssant_extrinsic_.ant_num << " "
118 << imu_gnssant_extrinsic_.transform_1.translation()[0] << " "
119 << imu_gnssant_extrinsic_.transform_1.translation()[1] << " "
120 << imu_gnssant_extrinsic_.transform_1.translation()[2] << " "
121 << imu_gnssant_extrinsic_.transform_2.translation()[0] << " "
122 << imu_gnssant_extrinsic_.transform_2.translation()[1] << " "
123 << imu_gnssant_extrinsic_.transform_2.translation()[2];
124
125 is_using_novatel_heading_ = params.is_using_novatel_heading;
126 if (imu_gnssant_extrinsic_.ant_num == 1) {
127 is_using_novatel_heading_ = false;
128 }
129 return Status::OK();
130}
static Status OK()
generate a success status.
Definition status.h:60
bool LoadImuGnssAntennaExtrinsic(std::string file_path, VehicleGnssAntExtrinsic *extrinsic) const
static void QuaternionToDcm(const double *quaternion, double dcm[3][3])
Definition math_util.h:41

◆ IntegPvaProcess()

void apollo::localization::msf::MeasureRepublishProcess::IntegPvaProcess ( const InsPva &  inspva_msg)

在文件 measure_republish_process.cc322 行定义.

322 {
323 const InsPva& integ_pva = inspva_msg;
324
325 std::lock_guard<std::mutex> lock(integ_pva_mutex_);
326 if (integ_pva_list_.size() < pva_buffer_size_) {
327 integ_pva_list_.push_back(integ_pva);
328 } else {
329 integ_pva_list_.pop_front();
330 integ_pva_list_.push_back(integ_pva);
331 }
332}

◆ IsSinsAlign()

bool apollo::localization::msf::MeasureRepublishProcess::IsSinsAlign ( )
protected

在文件 measure_republish_process.cc398 行定义.

398 {
399 std::lock_guard<std::mutex> lock(integ_pva_mutex_);
400 return !integ_pva_list_.empty() && integ_pva_list_.back().init_and_alignment;
401}

◆ LidarLocalProcess()

bool apollo::localization::msf::MeasureRepublishProcess::LidarLocalProcess ( const LocalizationEstimate lidar_local_msg,
MeasureData *  measure 
)

在文件 measure_republish_process.cc334 行定义.

335 {
336 CHECK_NOTNULL(measure);
337
338 MeasureData measure_data;
339 measure_data.time = lidar_local_msg.measurement_time();
340
343 lidar_local_msg.pose().position().x(),
344 lidar_local_msg.pose().position().y(), local_utm_zone_id_, false,
345 &temp_wgs);
346 measure_data.gnss_pos.longitude = temp_wgs.log;
347 measure_data.gnss_pos.latitude = temp_wgs.lat;
348 measure_data.gnss_pos.height = lidar_local_msg.pose().position().z();
349
350 Eigen::Quaterniond temp_quat(lidar_local_msg.pose().orientation().qw(),
351 lidar_local_msg.pose().orientation().qx(),
352 lidar_local_msg.pose().orientation().qy(),
353 lidar_local_msg.pose().orientation().qz());
354
355 common::math::EulerAnglesZXYd euler(temp_quat.w(), temp_quat.x(),
356 temp_quat.y(), temp_quat.z());
357
358 height_mutex_.lock();
359 Eigen::Vector3d trans(lidar_local_msg.pose().position().x(),
360 lidar_local_msg.pose().position().y(),
361 lidar_local_msg.pose().position().z());
362
363 map_height_time_ = measure_data.time;
364 height_mutex_.unlock();
365
366 measure_data.gnss_att.yaw = euler.yaw();
367 measure_data.measure_type = MeasureType::POINT_CLOUD_POS;
368 measure_data.frame_type = FrameType::UTM;
369
370 measure_data.is_have_variance = true;
371
372 double longitude_var = lidar_local_msg.uncertainty().position_std_dev().x();
373 double latitude_var = lidar_local_msg.uncertainty().position_std_dev().y();
374 double yaw_var = lidar_local_msg.uncertainty().orientation_std_dev().z();
375
376 static constexpr double height_var = 0.03 * 0.03;
377 measure_data.variance[0][0] = longitude_var;
378 measure_data.variance[1][1] = latitude_var;
379 measure_data.variance[2][2] = height_var;
380 measure_data.variance[8][8] = yaw_var;
381
382 *measure = measure_data;
383
384 ADEBUG << std::setprecision(16)
385 << "MeasureDataRepublish Debug Log: lidarLocal msg: "
386 << "[time:" << measure_data.time << "]"
387 << "[x:" << measure_data.gnss_pos.longitude * RAD_TO_DEG << "]"
388 << "[y:" << measure_data.gnss_pos.latitude * RAD_TO_DEG << "]"
389 << "[z:" << measure_data.gnss_pos.height << "]"
390 << "[yaw:" << measure_data.gnss_att.yaw * RAD_TO_DEG << "]"
391 << "[std_x:" << std::sqrt(longitude_var) << "]"
392 << "[std_y:" << std::sqrt(latitude_var) << "]"
393 << "[std_z:" << std::sqrt(height_var) << "]";
394
395 return true;
396}
static bool UtmXYToLatlon(double x, double y, int zone, bool southhemi, WGS84Corr *latlon)
EulerAnglesZXY< double > EulerAnglesZXYd
the WGS84 coordinate struct

◆ LoadImuGnssAntennaExtrinsic()

bool apollo::localization::msf::MeasureRepublishProcess::LoadImuGnssAntennaExtrinsic ( std::string  file_path,
VehicleGnssAntExtrinsic extrinsic 
) const
protected

在文件 measure_republish_process.cc635 行定义.

636 {
637 YAML::Node confige = YAML::LoadFile(file_path);
638 if (confige["leverarm"]) {
639 if (confige["leverarm"]["primary"]["offset"]) {
640 extrinsic->transform_1.translation()[0] =
641 confige["leverarm"]["primary"]["offset"]["x"].as<double>();
642 extrinsic->transform_1.translation()[1] =
643 confige["leverarm"]["primary"]["offset"]["y"].as<double>();
644 extrinsic->transform_1.translation()[2] =
645 confige["leverarm"]["primary"]["offset"]["z"].as<double>();
646 } else {
647 return false;
648 }
649 if (confige["leverarm"]["secondary"]["offset"]) {
650 extrinsic->transform_2.translation()[0] =
651 confige["leverarm"]["secondary"]["offset"]["x"].as<double>();
652 extrinsic->transform_2.translation()[1] =
653 confige["leverarm"]["secondary"]["offset"]["y"].as<double>();
654 extrinsic->transform_2.translation()[2] =
655 confige["leverarm"]["secondary"]["offset"]["z"].as<double>();
656 extrinsic->ant_num = 2;
657
658 if (confige["leverarm"]["secondary"]["rotation"]) {
659 double qx =
660 confige["leverarm"]["secondary"]["rotation"]["x"].as<double>();
661 double qy =
662 confige["leverarm"]["secondary"]["rotation"]["y"].as<double>();
663 double qz =
664 confige["leverarm"]["secondary"]["rotation"]["z"].as<double>();
665 double qw =
666 confige["leverarm"]["secondary"]["rotation"]["w"].as<double>();
667 extrinsic->transform_1.linear() =
668 Eigen::Quaterniond(qw, qx, qy, qz).toRotationMatrix();
669 } else {
670 double yaw = atan2(extrinsic->transform_2.translation()[0] -
671 extrinsic->transform_1.translation()[0],
672 extrinsic->transform_2.translation()[1] -
673 extrinsic->transform_1.translation()[1]);
674 double quat[4] = {0.0};
675 math::EulerToQuaternion(0.0, 0.0, yaw, quat);
676 extrinsic->transform_1.linear() =
677 Eigen::Quaterniond(quat[0], quat[1], quat[2], quat[3])
678 .toRotationMatrix();
679 }
680 return true;
681 } else {
682 extrinsic->ant_num = 1;
683 return true;
684 }
685 }
686 return false;
687}
static void EulerToQuaternion(const double x_euler, const double y_euler, const double z_euler, double qbn[4])
Definition math_util.h:27

◆ NovatelBestgnssposProcess()

bool apollo::localization::msf::MeasureRepublishProcess::NovatelBestgnssposProcess ( const GnssBestPose bestgnsspos_msg,
MeasureData *  measure 
)

在文件 measure_republish_process.cc132 行定义.

133 {
134 if (gnss_mode_ != GnssMode::NOVATEL) {
135 return false;
136 }
137 CHECK_NOTNULL(measure);
138
139 if (!CheckBestgnssposeStatus(bestgnsspos_msg)) {
140 AWARN << "Discard a bestgnsspose msg. "
141 << "The status of this msg is not OK.";
142 return false;
143 }
144
145 // check sins status
146 bool is_sins_align = IsSinsAlign();
147
148 // If sins is align, we only need measure of xyz from bestgnsspos.
149 // If sins is not align, in order to init sins, we need
150 // (1) send an initial measure of xyz; (2) send measure of xyz and velocity.
151 if (is_sins_align) {
152 TransferXYZFromBestgnsspose(bestgnsspos_msg, measure);
153 } else {
154 if (!CheckBestgnssPoseXYStd(bestgnsspos_msg)) {
155 AWARN << "Discard a bestgnsspose msg for large std.";
156 return false;
157 }
158
159 if (!send_init_bestgnsspose_) {
160 TransferFirstMeasureFromBestgnsspose(bestgnsspos_msg, measure);
161 send_init_bestgnsspose_ = true;
162 } else {
163 if (!CalculateVelFromBestgnsspose(bestgnsspos_msg, measure)) {
164 AINFO << "Waiting calculate velocity successfully...";
165 return false;
166 }
167 }
168 }
169
170 ADEBUG << std::setprecision(16)
171 << "MeasureDataRepublish Debug Log: bestgnsspos msg: "
172 << "[time:" << measure->time << "]"
173 << "[x:" << measure->gnss_pos.longitude * RAD_TO_DEG << "]"
174 << "[y:" << measure->gnss_pos.latitude * RAD_TO_DEG << "]"
175 << "[z:" << measure->gnss_pos.height << "]"
176 << "[std_x:" << bestgnsspos_msg.longitude_std_dev() << "]"
177 << "[std_y:" << bestgnsspos_msg.latitude_std_dev() << "]"
178 << "[std_z:" << bestgnsspos_msg.height_std_dev() << "]"
179 << "[position_type:" << bestgnsspos_msg.sol_type() << "]";
180
181 return true;
182}
void TransferFirstMeasureFromBestgnsspose(const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
bool CalculateVelFromBestgnsspose(const GnssBestPose &bestgnsspos_msg, MeasureData *measure)
bool CheckBestgnssposeStatus(const GnssBestPose &bestgnsspos_msg)
bool CheckBestgnssPoseXYStd(const GnssBestPose &bestgnsspos_msg)

◆ TransferFirstMeasureFromBestgnsspose()

void apollo::localization::msf::MeasureRepublishProcess::TransferFirstMeasureFromBestgnsspose ( const GnssBestPose bestgnsspos_msg,
MeasureData *  measure 
)
protected

在文件 measure_republish_process.cc434 行定义.

435 {
436 CHECK_NOTNULL(measure);
437
438 TransferXYZFromBestgnsspose(bestgnsspos_msg, measure);
439
440 measure->measure_type = MeasureType::GNSS_POS_VEL;
441 measure->frame_type = FrameType::ENU;
442 measure->is_have_variance = false;
443
444 measure->gnss_vel.ve = 0.0;
445 measure->gnss_vel.vn = 0.0;
446 measure->gnss_vel.vu = 0.0;
447 AINFO << "Novatel bestgnsspose publish: "
448 << "send sins init position using novatel bestgnsspos!";
449}

◆ TransferXYZFromBestgnsspose()

void apollo::localization::msf::MeasureRepublishProcess::TransferXYZFromBestgnsspose ( const GnssBestPose bestgnsspos_msg,
MeasureData *  measure 
)
protected

在文件 measure_republish_process.cc403 行定义.

404 {
405 CHECK_NOTNULL(measure);
406
407 measure->time = bestgnsspos_msg.measurement_time();
408 if (is_trans_gpstime_to_utctime_) {
409 measure->time = TimeUtil::Gps2Unix(measure->time);
410 }
411
412 measure->gnss_pos.longitude = bestgnsspos_msg.longitude() * DEG_TO_RAD;
413 measure->gnss_pos.latitude = bestgnsspos_msg.latitude() * DEG_TO_RAD;
414 measure->gnss_pos.height =
415 bestgnsspos_msg.height_msl() + bestgnsspos_msg.undulation();
416
417 measure->variance[0][0] =
418 bestgnsspos_msg.longitude_std_dev() * bestgnsspos_msg.longitude_std_dev();
419 measure->variance[1][1] =
420 bestgnsspos_msg.latitude_std_dev() * bestgnsspos_msg.latitude_std_dev();
421 measure->variance[2][2] =
422 bestgnsspos_msg.height_std_dev() * bestgnsspos_msg.height_std_dev();
423
424 measure->measure_type = MeasureType::GNSS_POS_ONLY;
425 measure->frame_type = FrameType::ENU;
426 height_mutex_.lock();
427 if ((measure->time - 1.0 < map_height_time_)) {
428 measure->measure_type = MeasureType::GNSS_POS_XY;
429 }
430 height_mutex_.unlock();
431 measure->is_have_variance = true;
432}

该类的文档由以下文件生成: