185 {
187 return;
188 }
189
190 CHECK_NOTNULL(measure);
191
192 MeasureData measure_data = gnss_local_msg;
193 if (is_trans_gpstime_to_utctime_) {
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
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
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: "
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)