Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Start using altitude getter - towards private alt in Location #28481

Open
wants to merge 13 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions libraries/AC_Avoidance/AC_Avoidance_Logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ void AP_OABendyRuler::Write_OABendyRuler(const uint8_t type, const bool active,
margin : margin,
final_lat : final_dest.lat,
final_lng : final_dest.lng,
final_alt : got_final_dest ? final_alt : final_dest.alt,
final_alt : got_final_dest ? final_alt : final_dest.get_alt_cm(),
oa_lat : oa_dest.lat,
oa_lng : oa_dest.lng,
oa_alt : got_oa_dest ? oa_dest_alt : oa_dest.alt
oa_alt : got_oa_dest ? oa_dest_alt : oa_dest.get_alt_cm()
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AC_WPNav/AC_WPNav_OA.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ bool AC_WPNav_OA::update_wpnav()
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return false;
}
Vector3p dest_NEU{dest_NE.x, dest_NE.y, (float)target_alt_loc.alt};
Vector3p dest_NEU{dest_NE.x, dest_NE.y, (float)target_alt_loc.get_alt_cm()};

// pass the desired position directly to the position controller
_pos_control.input_pos_xyz(dest_NEU, terr_offset, 1000.0);
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ADSB/AP_ADSB_Sagetech.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,12 +94,12 @@ void AP_ADSB_Sagetech::update()
last_packet_Operating_ms == 0 || // send once at boot
// send as data changes
last_operating_squawk != _frontend.out_state.cfg.squawk_octal ||
abs(last_operating_alt - _frontend._my_loc.alt) > 1555 || // 1493cm == 49ft. The output resolution is 100ft per bit
abs(last_operating_alt - _frontend._my_loc.get_alt_cm()) > 1555 || // 1493cm == 49ft. The output resolution is 100ft per bit
last_operating_rf_select != _frontend.out_state.cfg.rfSelect))
{
last_packet_Operating_ms = now_ms;
last_operating_squawk = _frontend.out_state.cfg.squawk_octal;
last_operating_alt = _frontend._my_loc.alt;
last_operating_alt = _frontend._my_loc.get_alt_cm();
last_operating_rf_select = _frontend.out_state.cfg.rfSelect;
send_packet(MsgType_XP::Operating_Set);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) co

const int32_t latitude = _frontend._my_loc.lat;
const int32_t longitude = _frontend._my_loc.lng;
const int32_t altGNSS = _frontend._my_loc.alt * 10; // convert cm to mm
const int32_t altGNSS = _frontend._my_loc.get_alt_cm() * 10; // convert cm to mm
const int16_t velVert = -1.0f * gps_velocity.z * 1E2; // convert m/s to cm/s
const int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s
const int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,7 @@ void AP_ADSB_uAvionix_UCP::send_GPS_Data()
msg.utcTime_s = gps.time_epoch_usec() * 1E-6;
msg.latitude_ddE7 = fix_is_good ? _frontend._my_loc.lat : INT32_MAX;
msg.longitude_ddE7 = fix_is_good ? _frontend._my_loc.lng : INT32_MAX;
msg.altitudeGnss_mm = fix_is_good ? (_frontend._my_loc.alt * 10): INT32_MAX;
msg.altitudeGnss_mm = fix_is_good ? (_frontend._my_loc.get_alt_cm() * 10): INT32_MAX;

// Protection Limits. FD or SBAS-based depending on state bits
msg.HPL_mm = UINT32_MAX;
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS_External.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ bool AP_AHRS_External::get_relative_position_NED_origin(Vector3f &vec) const
extahrs.get_location(loc)) {
const Vector2f diff2d = orgn.get_distance_NE(loc);
vec = Vector3f(diff2d.x, diff2d.y,
-(loc.alt - orgn.alt)*0.01);
-(loc.get_alt_cm() - orgn.get_alt_cm())*0.01);
return true;
}
return false;
Expand Down Expand Up @@ -95,7 +95,7 @@ bool AP_AHRS_External::get_relative_position_D_origin(float &posD) const
!extahrs.get_location(loc)) {
return false;
}
posD = -(loc.alt - orgn.alt)*0.01;
posD = -(loc.get_alt_cm() - orgn.get_alt_cm())*0.01;
return true;
}

Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_AHRS/AP_AHRS_Logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ void AP_AHRS::Write_AHRS2() const
roll : (int16_t)(degrees(euler.x)*100),
pitch : (int16_t)(degrees(euler.y)*100),
yaw : (uint16_t)(wrap_360_cd(degrees(euler.z)*100)),
alt : loc.alt*1.0e-2f,
alt : loc.get_alt_cm()*1.0e-2f,
lat : loc.lat,
lng : loc.lng,
q1 : quat.q1,
Expand Down Expand Up @@ -73,7 +73,7 @@ void AP_AHRS::Write_Origin(LogOriginType origin_type, const Location &loc) const
origin_type : (uint8_t)origin_type,
latitude : loc.lat,
longitude : loc.lng,
altitude : loc.alt
altitude : loc.get_alt_cm()
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
Expand All @@ -92,7 +92,7 @@ void AP_AHRS::Write_POS() const
time_us : AP_HAL::micros64(),
lat : loc.lat,
lng : loc.lng,
alt : loc.alt*1.0e-2f,
alt : loc.get_alt_cm()*1.0e-2f,
rel_home_alt : -home,
rel_origin_alt : get_relative_position_D_origin(origin) ? -origin : AP::logger().quiet_nanf(),
};
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_AHRS/AP_AHRS_SIM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ bool AP_AHRS_SIM::get_location(Location &loc) const
loc = {};
loc.lat = fdm.latitude * 1e7;
loc.lng = fdm.longitude * 1e7;
loc.alt = fdm.altitude*100;
loc.set_alt_cm(fdm.altitude*100, Location::AltFrame::ABSOLUTE);

return true;
}
Expand Down Expand Up @@ -97,7 +97,7 @@ bool AP_AHRS_SIM::get_hagl(float &height) const
return false;
}

height = _sitl->state.altitude - AP::ahrs().get_home().alt*0.01f;
height = _sitl->state.altitude - AP::ahrs().get_home().get_alt_cm()*0.01f;

return true;
}
Expand All @@ -117,7 +117,7 @@ bool AP_AHRS_SIM::get_relative_position_NED_origin(Vector3f &vec) const
const Vector2f diff2d = orgn.get_distance_NE(loc);
const struct SITL::sitl_fdm &fdm = _sitl->state;
vec = Vector3f(diff2d.x, diff2d.y,
-(fdm.altitude - orgn.alt*0.01f));
-(fdm.altitude - orgn.get_alt_cm()*0.01f));

return true;
}
Expand All @@ -144,7 +144,7 @@ bool AP_AHRS_SIM::get_relative_position_D_origin(float &posD) const
if (!get_origin(orgn)) {
return false;
}
posD = -(fdm.altitude - orgn.alt*0.01f);
posD = -(fdm.altitude - orgn.get_alt_cm()*0.01f);

return true;
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -378,7 +378,7 @@ AP_AdvancedFailsafe::check_altlimit(void)
// the barometer has been unresponsive for 5 seconds. See if we can switch to GPS
if (_amsl_margin_gps != -1 &&
gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
gps.location().alt*0.01f <= _amsl_limit - _amsl_margin_gps) {
gps.location().get_alt_cm()*0.01f <= _amsl_limit - _amsl_margin_gps) {
// GPS based altitude OK
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Beacon/AP_Beacon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ bool AP_Beacon::get_origin(Location &origin_loc) const
origin_loc = {};
origin_loc.lat = origin_lat * 1.0e7f;
origin_loc.lng = origin_lon * 1.0e7f;
origin_loc.alt = origin_alt * 100;
origin_loc.set_alt_cm(origin_alt * 100, Location::AltFrame::ABSOLUTE);

return true;
}
Expand Down
8 changes: 4 additions & 4 deletions libraries/AP_Beacon/AP_Beacon_SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,13 +69,13 @@ void AP_Beacon_SITL::update(void)
Location current_loc;
current_loc.lat = sitl->state.latitude * 1.0e7f;
current_loc.lng = sitl->state.longitude * 1.0e7f;
current_loc.alt = sitl->state.altitude * 1.0e2;
current_loc.set_alt_cm(sitl->state.altitude * 1.0e2, Location::AltFrame::ABSOLUTE);

// where the beacon system origin is located
Location beacon_origin;
beacon_origin.lat = get_beacon_origin_lat() * 1.0e7f;
beacon_origin.lng = get_beacon_origin_lon() * 1.0e7f;
beacon_origin.alt = get_beacon_origin_alt() * 1.0e2;
beacon_origin.set_alt_cm(get_beacon_origin_alt() * 1.0e2, Location::AltFrame::ABSOLUTE);

// position of each beacon
Location beacon_loc = beacon_origin;
Expand All @@ -101,8 +101,8 @@ void AP_Beacon_SITL::update(void)
const Vector2f beac_diff = beacon_origin.get_distance_NE(beacon_loc);
const Vector2f veh_diff = beacon_origin.get_distance_NE(current_loc);

Vector3f veh_pos3d(veh_diff.x, veh_diff.y, (beacon_origin.alt - current_loc.alt)*1.0e-2f);
Vector3f beac_pos3d(beac_diff.x, beac_diff.y, (beacon_loc.alt - beacon_origin.alt)*1.0e-2f);
Vector3f veh_pos3d(veh_diff.x, veh_diff.y, (beacon_origin.get_alt_cm() - current_loc.get_alt_cm())*1.0e-2f);
Vector3f beac_pos3d(beac_diff.x, beac_diff.y, (beacon_loc.get_alt_cm() - beacon_origin.get_alt_cm())*1.0e-2f);
Vector3f beac_veh_offset = veh_pos3d - beac_pos3d;

set_beacon_position(beacon_id, beac_pos3d);
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -318,10 +318,10 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const
AP_HAL::millis(),
loc.lat,
loc.lng,
loc.alt * 10,
loc.get_alt_cm() * 10,
poi_loc.lat,
poi_loc.lng,
poi_loc.alt * 10,
poi_loc.get_alt_cm() * 10,
quat_array,
horizontal_fov() > 0 ? horizontal_fov() : NaNf,
vertical_fov() > 0 ? vertical_fov() : NaNf
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_Common/Location.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,11 @@ class Location
// - above-home and home is not set
// - above-origin and origin is not set
bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const WARN_IF_UNUSED;

// retrieve the altitude (in cm) in the stored frame.
int32_t get_alt_cm() const WARN_IF_UNUSED {
return alt;
}
// same as get_alt_cm but in metres:
bool get_alt_m(AltFrame desired_frame, float &ret_alt) const WARN_IF_UNUSED;

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DAL/AP_DAL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
_home = ahrs.get_home();
_RFRN.lat = _home.lat;
_RFRN.lng = _home.lng;
_RFRN.alt = _home.alt;
_RFRN.alt = _home.get_alt_cm();
_RFRN.EAS2TAS = ahrs.get_EAS2TAS();
_RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class();
_RFRN.fly_forward = ahrs.get_fly_forward();
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DAL/AP_DAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ class AP_DAL {
_RFRN = msg;
_home.lat = msg.lat;
_home.lng = msg.lng;
_home.alt = msg.alt;
_home.set_alt_cm(msg.alt, Location::AltFrame::ABSOLUTE);
}
void handle_message(const log_RFRF &msg, NavEKF2 &ekf2, NavEKF3 &ekf3);

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DAL/AP_DAL_Beacon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ void AP_DAL_Beacon::start_frame()
_RBCH.enabled = bcon->enabled();
_RBCH.origin_lat = loc.lat;
_RBCH.origin_lng = loc.lng;
_RBCH.origin_alt = loc.alt;
_RBCH.origin_alt = loc.get_alt_cm();
}
WRITE_REPLAY_BLOCK_IFCHANGED(RBCH, _RBCH, old);
if (bcon == nullptr) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DAL/AP_DAL_Beacon.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class AP_DAL_Beacon {
loc.zero();
loc.lat = _RBCH.origin_lat;
loc.lng = _RBCH.origin_lng;
loc.alt = _RBCH.origin_alt;
loc.set_alt_cm(_RBCH.origin_alt, Location::AltFrame::ABSOLUTE);
return _RBCH.get_origin_returncode;
}

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_DAL/AP_DAL_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ void AP_DAL_GPS::start_frame()
RGPJ.last_message_time_ms = gps.last_message_time_ms(i);
RGPJ.lat = loc.lat;
RGPJ.lng = loc.lng;
RGPJ.alt = loc.alt;
RGPJ.alt = loc.get_alt_cm();
RGPI.have_vertical_velocity = gps.have_vertical_velocity(i);

RGPI.horizontal_accuracy_returncode = gps.horizontal_accuracy(i, RGPJ.hacc);
Expand All @@ -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);
}
}
2 changes: 1 addition & 1 deletion libraries/AP_DAL/AP_DAL_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ class AP_DAL_GPS {

tmp_location[msg.instance].lat = msg.lat;
tmp_location[msg.instance].lng = msg.lng;
tmp_location[msg.instance].alt = msg.alt;
tmp_location[msg.instance].set_alt_cm(msg.alt, Location::AltFrame::ABSOLUTE);
}

private:
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_DAL/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,23 +41,23 @@
LOG_RBOH_MSG

// @LoggerMessage: RFRH
// @Description: Replay FRame Header
// @Description: Replay Frame Header
struct log_RFRH {
uint64_t time_us;
uint32_t time_flying_ms;
uint8_t _end;
};

// @LoggerMessage: RFRF
// @Description: Replay FRame data - Finished frame
// @Description: Replay Frame data - Finished frame
struct log_RFRF {
uint8_t frame_types;
uint8_t core_slow;
uint8_t _end;
};

// @LoggerMessage: RFRN
// @Description: Replay FRame - aNother frame header
// @Description: Replay Frame - another frame header
struct log_RFRN {
int32_t lat;
int32_t lng;
Expand Down
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
4 changes: 2 additions & 2 deletions libraries/AP_GPS/AP_GPS_Blended.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -321,13 +321,13 @@ void AP_GPS_Blended::calc_state(void)
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
if (_blend_weights[i] > 0.0f && i != best_index) {
blended_NE_offset_m += state.location.get_distance_NE(gps.state[i].location) * _blend_weights[i];
blended_alt_offset_cm += (float)(gps.state[i].location.alt - state.location.alt) * _blend_weights[i];
blended_alt_offset_cm += (float)(gps.state[i].location.get_alt_cm() - state.location.get_alt_cm()) * _blend_weights[i];
}
}

// 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_ExternalAHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void AP_GPS_ExternalAHRS::handle_external(const AP_ExternalAHRS::gps_data_messag
Location loc = {};
loc.lat = pkt.latitude;
loc.lng = pkt.longitude;
loc.alt = pkt.msl_altitude;
loc.set_alt_cm(pkt.msl_altitude, Location::AltFrame::ABSOLUTE);

state.location = loc;
state.hdop = pkt.hdop;
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_MAV.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t &msg)
loc.lat = packet.lat;
loc.lng = packet.lon;
if (have_alt) {
loc.alt = packet.alt * 100; // convert to centimeters
loc.set_alt_cm(packet.alt * 100, Location::AltFrame::ABSOLUTE);
}
state.location = loc;

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS_MSP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ void AP_GPS_MSP::handle_msp(const MSP::msp_gps_data_message_t &pkt)
Location loc = {};
loc.lat = pkt.latitude;
loc.lng = pkt.longitude;
loc.alt = pkt.msl_altitude;
loc.set_alt_cm(pkt.msl_altitude, Location::AltFrame::ABSOLUTE);

state.location = loc;
state.hdop = pkt.hdop;
Expand Down
Loading
Loading