Skip to content

Commit

Permalink
use alt getter/setter instead of member
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Oct 20, 2024
1 parent 7ff4ca9 commit 79ca8a0
Show file tree
Hide file tree
Showing 9 changed files with 12 additions and 12 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_DAL/AP_DAL_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,6 @@ void AP_DAL_GPS::start_frame()

tmp_location[i].lat = RGPJ.lat;
tmp_location[i].lng = RGPJ.lng;
tmp_location[i].alt = RGPJ.alt;
tmp_location[i].set_alt_cm(RGPJ.alt, Location::AltFrame::ABSOLUTE);
}
}
4 changes: 2 additions & 2 deletions libraries/AP_DroneCAN/AP_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1092,8 +1092,8 @@ void AP_DroneCAN::gnss_send_fix()
}
pkt.longitude_deg_1e8 = uint64_t(loc.lng) * 10ULL;
pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL;
pkt.height_ellipsoid_mm = loc.alt * 10;
pkt.height_msl_mm = loc.alt * 10;
pkt.height_ellipsoid_mm = loc.get_alt_cm() * 10;
pkt.height_msl_mm = loc.get_alt_cm() * 10;
for (uint8_t i=0; i<3; i++) {
pkt.ned_velocity[i] = vel[i];
}
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,8 @@ void AP_ExternalAHRS::update(void)
AP_HAL::micros64(),
degrees(roll), degrees(pitch), degrees(yaw),
state.velocity.x, state.velocity.y, state.velocity.z,
state.location.lat, state.location.lng, state.location.alt*0.01,
state.location.lat, state.location.lng,
state.location.get_alt_cm()*0.01,
filterStatus.value);
}
#endif // HAL_LOGGING_ENABLED
Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,6 @@ void AP_Frsky_Backend::calc_gps_position(void)
AP_AHRS &_ahrs = AP::ahrs();

Location loc;

if (_ahrs.get_location(loc)) {
float lat = format_gps(fabsf(loc.lat/10000000.0f));
_SPort_data.latdddmm = lat;
Expand All @@ -89,7 +88,7 @@ void AP_Frsky_Backend::calc_gps_position(void)
_SPort_data.lonmmmm = (lon - _SPort_data.londddmm) * 10000;
_SPort_data.lon_ew = (loc.lng < 0) ? 'W' : 'E';

float alt = loc.alt * 0.01f;
float alt = loc.get_alt_cm() * 0.01f;
_SPort_data.alt_gps_meters = float_to_uint16(alt);
_SPort_data.alt_gps_cm = float_to_uint16((alt - _SPort_data.alt_gps_meters) * 100);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1376,7 +1376,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
float undulation = 0.0;
int32_t height_elipsoid_mm = 0;
if (get_undulation(0, undulation)) {
height_elipsoid_mm = loc.alt*10 - undulation*1000;
height_elipsoid_mm = loc.get_alt_cm()*10 - undulation*1000;
}
horizontal_accuracy(0, hacc);
vertical_accuracy(0, vacc);
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS_Blended.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,7 +327,7 @@ void AP_GPS_Blended::calc_state(void)

// Add the sum of weighted offsets to the reference location to obtain the blended location
state.location.offset(blended_NE_offset_m.x, blended_NE_offset_m.y);
state.location.alt += (int)blended_alt_offset_cm;
state.location.set_alt_cm(state.location.get_alt_cm() + (int)blended_alt_offset_cm, Location::AltFrame::ABSOLUTE);

// Calculate ground speed and course from blended velocity vector
state.ground_speed = state.velocity.xy().length();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS_GSOF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ AP_GPS_GSOF::pack_state_data()

state.location.lat = (int32_t)(RAD_TO_DEG_DOUBLE * position.latitude_rad * (double)1e7);
state.location.lng = (int32_t)(RAD_TO_DEG_DOUBLE * position.longitude_rad * (double)1e7);
state.location.alt = (int32_t)(position.altitude * 100);
state.location.set_alt_cm((int32_t)(position.altitude * 100), Location::AltFrame::ABSOLUTE);
state.last_gps_time_ms = AP_HAL::millis();

if ((vel.velocity_flags & 1) == 1) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS_SBP2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,7 @@ AP_GPS_SBP2::_attempt_state_update()
//
state.location.lat = (int32_t) (last_pos_llh.lat * (double)1e7);
state.location.lng = (int32_t) (last_pos_llh.lon * (double)1e7);
state.location.alt = (int32_t) (last_pos_llh.height * 100);
state.location.set_alt_cm((int32_t) (last_pos_llh.height * 100), Location::AltFrame::ABSOLUTE);
state.num_sats = last_pos_llh.n_sats;

switch (last_pos_llh.flags.fix_mode) {
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_GPS/GPS_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -459,9 +459,9 @@ void AP_GPS_Backend::set_alt_amsl_cm(AP_GPS::GPS_State &_state, int32_t alt_amsl
if (option_set(AP_GPS::HeightEllipsoid) && _state.have_undulation) {
// user has asked ArduPilot to use ellipsoid height in the
// canonical height for mission and navigation
_state.location.alt = alt_amsl_cm - _state.undulation*100;
_state.location.set_alt_cm(alt_amsl_cm - _state.undulation*100, Location::AltFrame::ABSOLUTE);
} else {
_state.location.alt = alt_amsl_cm;
_state.location.set_alt_cm(alt_amsl_cm, Location::AltFrame::ABSOLUTE);
}
}

Expand Down

0 comments on commit 79ca8a0

Please sign in to comment.