@@ -2424,52 +2424,71 @@ class MavlinkStreamGlobalPositionInt : public MavlinkStream
2424
2424
2425
2425
bool send (const hrt_abstime t) override
2426
2426
{
2427
- vehicle_global_position_s gpos;
2428
2427
vehicle_local_position_s lpos;
2429
2428
2430
- if (_gpos_sub.update (&gpos) && _lpos_sub.update (&lpos)) {
2431
-
2429
+ if (_lpos_sub.update (&lpos)) {
2432
2430
mavlink_global_position_int_t msg{};
2433
2431
2432
+ // time_boot_ms: Timestamp (time since system boot) in ms.
2433
+ msg.time_boot_ms = lpos.timestamp / 1000 ;
2434
+
2435
+ // alt: Altitude (MSL) in mm.
2434
2436
if (lpos.z_valid && lpos.z_global ) {
2435
- msg.alt = (-lpos.z + lpos.ref_alt ) * 1000 .0f ;
2437
+ msg.alt = (-lpos.z + lpos.ref_alt ) * 1000 .f ;
2436
2438
2437
2439
} else {
2438
2440
// fall back to baro altitude
2439
2441
vehicle_air_data_s air_data{};
2440
- _air_data_sub.copy (&air_data);
2441
2442
2442
- if (air_data.timestamp > 0 ) {
2443
- msg.alt = air_data.baro_alt_meter * 1000 .0f ;
2443
+ if (_air_data_sub. copy (& air_data) && ( hrt_elapsed_time (&air_data .timestamp ) < 10_s) ) {
2444
+ msg.alt = air_data.baro_alt_meter * 1000 .f ;
2444
2445
}
2445
2446
}
2446
2447
2448
+ // relative_alt: Altitude above ground in mm
2447
2449
home_position_s home{};
2448
2450
_home_sub.copy (&home);
2449
2451
2450
2452
if ((home.timestamp > 0 ) && home.valid_alt ) {
2451
2453
if (lpos.z_valid ) {
2452
- msg.relative_alt = -(lpos.z - home.z ) * 1000 .0f ;
2454
+ msg.relative_alt = -(lpos.z - home.z ) * 1000 .f ;
2453
2455
2454
2456
} else {
2455
- msg.relative_alt = msg.alt - (home.alt * 1000 .0f );
2457
+ msg.relative_alt = msg.alt - (home.alt * 1000 .f );
2456
2458
}
2457
2459
2458
2460
} else {
2459
2461
if (lpos.z_valid ) {
2460
- msg.relative_alt = -lpos.z * 1000 .0f ;
2462
+ msg.relative_alt = -lpos.z * 1000 .f ;
2461
2463
}
2462
2464
}
2463
2465
2464
- msg.time_boot_ms = gpos.timestamp / 1000 ;
2465
- msg.lat = gpos.lat * 1e7 ;
2466
- msg.lon = gpos.lon * 1e7 ;
2466
+ // lat, lon: Latitude, Longitude in degE7
2467
+ vehicle_global_position_s gpos{};
2467
2468
2468
- msg.vx = lpos.vx * 100 .0f ;
2469
- msg.vy = lpos.vy * 100 .0f ;
2470
- msg.vz = lpos.vz * 100 .0f ;
2469
+ if (_gpos_sub.copy (&gpos) && (hrt_elapsed_time (&gpos.timestamp ) < 10_s)) {
2470
+ msg.lat = gpos.lat * 1e7 ;
2471
+ msg.lon = gpos.lon * 1e7 ;
2472
+ }
2473
+
2474
+ // vx, vy: Ground X, Y Speed (Latitude, positive north) in cm/s
2475
+ if (lpos.v_xy_valid ) {
2476
+ msg.vx = lpos.vx * 100 .f ;
2477
+ msg.vy = lpos.vy * 100 .f ;
2478
+ }
2471
2479
2472
- msg.hdg = math::degrees (wrap_2pi (lpos.yaw )) * 100 .0f ;
2480
+ // vz: Ground Z Speed (Altitude, positive down) in cm/s
2481
+ if (lpos.v_z_valid ) {
2482
+ msg.vz = lpos.vz * 100 .f ;
2483
+ }
2484
+
2485
+ // hdg: Vehicle heading (yaw angle) in cdeg, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
2486
+ if (PX4_ISFINITE (lpos.yaw )) {
2487
+ msg.hdg = math::degrees (wrap_2pi (lpos.yaw )) * 100 .f ;
2488
+
2489
+ } else {
2490
+ msg.hdg = UINT16_MAX;
2491
+ }
2473
2492
2474
2493
mavlink_msg_global_position_int_send_struct (_mavlink->get_channel (), &msg);
2475
2494
0 commit comments