@@ -28,19 +28,22 @@ void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestam
28
28
// completely ignore this failure! AHRS will provide its best guess.
29
29
}
30
30
31
- int32_t altitude, altitude_rel, altitude_gps;
32
- if (current_loc.relative_alt ) {
33
- altitude = current_loc.alt +ahrs.get_home ().alt ;
34
- altitude_rel = current_loc.alt ;
35
- } else {
36
- altitude = current_loc.alt ;
37
- altitude_rel = current_loc.alt - ahrs.get_home ().alt ;
31
+ int32_t altitude_cm = 0 ;
32
+ if (!current_loc.get_alt_cm (Location::AltFrame::ABSOLUTE, altitude_cm)) {
33
+ // ignore this problem...
38
34
}
35
+ int32_t altitude_rel_cm = 0 ;
36
+ if (!current_loc.get_alt_cm (Location::AltFrame::ABOVE_HOME, altitude_rel_cm)) {
37
+ // ignore this problem...
38
+ }
39
+
40
+
41
+ int32_t altitude_gps_cm = 0 ;
39
42
const AP_GPS &gps = AP::gps ();
40
43
if (gps.status () >= AP_GPS::GPS_OK_FIX_3D) {
41
- altitude_gps = gps.location ().alt ;
42
- } else {
43
- altitude_gps = 0 ;
44
+ if (! gps.location ().get_alt_cm (Location::AltFrame::ABSOLUTE, altitude_gps_cm)) {
45
+ // ignore this problem...
46
+ }
44
47
}
45
48
46
49
// if timestamp is zero set to current system time
@@ -57,9 +60,9 @@ void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestam
57
60
gps_week : gps.time_week(),
58
61
latitude : current_loc.lat,
59
62
longitude : current_loc.lng,
60
- altitude : altitude ,
61
- altitude_rel: altitude_rel ,
62
- altitude_gps: altitude_gps ,
63
+ altitude : altitude_cm ,
64
+ altitude_rel: altitude_rel_cm ,
65
+ altitude_gps: altitude_gps_cm ,
63
66
roll : (int16_t )ahrs.roll_sensor,
64
67
pitch : (int16_t )ahrs.pitch_sensor,
65
68
yaw : (uint16_t )ahrs.yaw_sensor
0 commit comments