mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_GPS: fixes for macos CAN SITL build
This commit is contained in:
parent
e6d43811ad
commit
74139423cb
@ -321,7 +321,7 @@ AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan,
|
||||
*/
|
||||
void AP_GPS_DroneCAN::handle_velocity(const float vx, const float vy, const float vz)
|
||||
{
|
||||
if (!isnanf(vx)) {
|
||||
if (!isnan(vx)) {
|
||||
const Vector3f vel(vx, vy, vz);
|
||||
interim_state.velocity = vel;
|
||||
velocity_to_speed_course(interim_state);
|
||||
@ -391,21 +391,21 @@ void AP_GPS_DroneCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uin
|
||||
handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]);
|
||||
|
||||
if (msg.covariance.len == 6) {
|
||||
if (!isnanf(msg.covariance.data[0])) {
|
||||
if (!isnan(msg.covariance.data[0])) {
|
||||
interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]);
|
||||
interim_state.have_horizontal_accuracy = true;
|
||||
} else {
|
||||
interim_state.have_horizontal_accuracy = false;
|
||||
}
|
||||
if (!isnanf(msg.covariance.data[2])) {
|
||||
if (!isnan(msg.covariance.data[2])) {
|
||||
interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]);
|
||||
interim_state.have_vertical_accuracy = true;
|
||||
} else {
|
||||
interim_state.have_vertical_accuracy = false;
|
||||
}
|
||||
if (!isnanf(msg.covariance.data[3]) &&
|
||||
!isnanf(msg.covariance.data[4]) &&
|
||||
!isnanf(msg.covariance.data[5])) {
|
||||
if (!isnan(msg.covariance.data[3]) &&
|
||||
!isnan(msg.covariance.data[4]) &&
|
||||
!isnan(msg.covariance.data[5])) {
|
||||
interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3);
|
||||
interim_state.have_speed_accuracy = true;
|
||||
} else {
|
||||
@ -479,12 +479,12 @@ void AP_GPS_DroneCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg)
|
||||
{
|
||||
WITH_SEMAPHORE(sem);
|
||||
|
||||
if (!isnanf(msg.hdop)) {
|
||||
if (!isnan(msg.hdop)) {
|
||||
seen_aux = true;
|
||||
interim_state.hdop = msg.hdop * 100.0;
|
||||
}
|
||||
|
||||
if (!isnanf(msg.vdop)) {
|
||||
if (!isnan(msg.vdop)) {
|
||||
seen_aux = true;
|
||||
interim_state.vdop = msg.vdop * 100.0;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user