mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: do not zero options after assigning from location
On the assumption that the assignment operator knows what it is doing, and that we have no idea what fields are actually present in options
This commit is contained in:
parent
38a649033f
commit
30d5d6b578
@ -819,7 +819,6 @@ void AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms
|
||||
GPS_State &istate = state[instance];
|
||||
istate.status = _status;
|
||||
istate.location = _location;
|
||||
istate.location.options = 0;
|
||||
istate.velocity = _velocity;
|
||||
istate.ground_speed = norm(istate.velocity.x, istate.velocity.y);
|
||||
istate.ground_course = wrap_360(degrees(atan2f(istate.velocity.y, istate.velocity.x)));
|
||||
|
@ -67,7 +67,6 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
|
||||
loc.alt = packet.alt * 100; // convert to centimeters
|
||||
}
|
||||
state.location = loc;
|
||||
state.location.options = 0;
|
||||
|
||||
if (have_hdop) {
|
||||
state.hdop = packet.hdop * 100; // convert to centimeters
|
||||
@ -123,7 +122,6 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
|
||||
loc.lng = packet.lon;
|
||||
loc.alt = packet.alt * 0.1f;
|
||||
state.location = loc;
|
||||
state.location.options = 0;
|
||||
state.hdop = MIN(packet.eph, GPS_UNKNOWN_DOP);
|
||||
state.vdop = MIN(packet.epv, GPS_UNKNOWN_DOP);
|
||||
if (packet.vel < 65535) {
|
||||
|
@ -186,7 +186,6 @@ void AP_GPS_UAVCAN::handle_fix_msg(const FixCb &cb)
|
||||
loc.lng = cb.msg->longitude_deg_1e8 / 10;
|
||||
loc.alt = cb.msg->height_msl_mm / 10;
|
||||
interim_state.location = loc;
|
||||
interim_state.location.options = 0;
|
||||
|
||||
if (!uavcan::isNaN(cb.msg->ned_velocity[0])) {
|
||||
Vector3f vel(cb.msg->ned_velocity[0], cb.msg->ned_velocity[1], cb.msg->ned_velocity[2]);
|
||||
|
Loading…
Reference in New Issue
Block a user