mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_GPS: initialise uavcan drv interim_state with state structure at startup
This commit is contained in:
parent
85d8becb8c
commit
3b58463bfd
@ -72,6 +72,7 @@ HAL_Semaphore AP_GPS_UAVCAN::_sem_registry;
|
||||
// Member Methods
|
||||
AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_GPS::GPS_Role _role) :
|
||||
AP_GPS_Backend(_gps, _state, nullptr),
|
||||
interim_state(_state),
|
||||
role(_role)
|
||||
{
|
||||
param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_UAVCAN::handle_param_get_set_response_int, bool, AP_UAVCAN*, const uint8_t, const char*, int32_t &);
|
||||
|
@ -385,11 +385,8 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state,
|
||||
{
|
||||
// at this point the offsets are looking okay, go ahead and actually calculate a useful heading
|
||||
const float rotation_offset_rad = Vector2f(-offset.x, -offset.y).angle();
|
||||
state.gps_yaw = wrap_360(reported_heading_deg - degrees(rotation_offset_rad));
|
||||
state.have_gps_yaw = true;
|
||||
state.gps_yaw_time_ms = AP_HAL::millis();
|
||||
interim_state.gps_yaw = state.gps_yaw;
|
||||
interim_state.have_gps_yaw = state.have_gps_yaw;
|
||||
interim_state.gps_yaw = wrap_360(reported_heading_deg - degrees(rotation_offset_rad));
|
||||
interim_state.have_gps_yaw = true;
|
||||
interim_state.gps_yaw_time_ms = AP_HAL::millis();
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user