mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS_SBF: formatting fixes
This commit is contained in:
parent
f8b0a6a977
commit
0bcc6e324a
@ -45,7 +45,7 @@ AP_GPS_SBF::AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state,
|
||||
{
|
||||
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
|
||||
|
||||
port->write((const uint8_t*)_initialisation_blob[0], strlen(_initialisation_blob[0]));
|
||||
port->write((const uint8_t*)_initialisation_blob[0], strlen(_initialisation_blob[0]));
|
||||
}
|
||||
|
||||
// Process all bytes available from the stream
|
||||
@ -199,7 +199,7 @@ AP_GPS_SBF::process_message(void)
|
||||
state.time_week_ms = (uint32_t)(temp.TOW);
|
||||
}
|
||||
|
||||
state.last_gps_time_ms = AP_HAL::millis();
|
||||
state.last_gps_time_ms = AP_HAL::millis();
|
||||
|
||||
state.hdop = last_hdop;
|
||||
|
||||
@ -209,7 +209,7 @@ AP_GPS_SBF::process_message(void)
|
||||
state.velocity.y = (float)(temp.Ve);
|
||||
state.velocity.z = (float)(-temp.Vu);
|
||||
|
||||
state.have_vertical_velocity = true;
|
||||
state.have_vertical_velocity = true;
|
||||
|
||||
float ground_vector_sq = state.velocity[0] * state.velocity[0] + state.velocity[1] * state.velocity[1];
|
||||
state.ground_speed = (float)safe_sqrt(ground_vector_sq);
|
||||
@ -217,10 +217,10 @@ AP_GPS_SBF::process_message(void)
|
||||
state.ground_course_cd = (int32_t)(100 * ToDeg(atan2f(state.velocity[1], state.velocity[0])));
|
||||
state.ground_course_cd = wrap_360_cd(state.ground_course_cd);
|
||||
|
||||
state.horizontal_accuracy = (float)temp.HAccuracy * 0.01f;
|
||||
state.vertical_accuracy = (float)temp.VAccuracy * 0.01f;
|
||||
state.have_horizontal_accuracy = true;
|
||||
state.have_vertical_accuracy = true;
|
||||
state.horizontal_accuracy = (float)temp.HAccuracy * 0.01f;
|
||||
state.vertical_accuracy = (float)temp.VAccuracy * 0.01f;
|
||||
state.have_horizontal_accuracy = true;
|
||||
state.have_vertical_accuracy = true;
|
||||
}
|
||||
|
||||
// Update position state (dont use −2·10^10)
|
||||
@ -278,7 +278,7 @@ AP_GPS_SBF::process_message(void)
|
||||
|
||||
last_hdop = temp.HDOP;
|
||||
|
||||
state.hdop = last_hdop;
|
||||
state.hdop = last_hdop;
|
||||
}
|
||||
|
||||
return false;
|
||||
|
@ -82,14 +82,14 @@ private:
|
||||
uint16_t MeanCorrAge;
|
||||
uint32_t SignalInfo;
|
||||
uint8_t AlertFlag;
|
||||
// rev1
|
||||
uint8_t NrBases;
|
||||
uint16_t PPPInfo;
|
||||
// rev2
|
||||
uint16_t Latency;
|
||||
uint16_t HAccuracy;
|
||||
uint16_t VAccuracy;
|
||||
uint8_t Misc;
|
||||
// rev1
|
||||
uint8_t NrBases;
|
||||
uint16_t PPPInfo;
|
||||
// rev2
|
||||
uint16_t Latency;
|
||||
uint16_t HAccuracy;
|
||||
uint16_t VAccuracy;
|
||||
uint8_t Misc;
|
||||
};
|
||||
|
||||
struct PACKED msg4001
|
||||
@ -106,9 +106,9 @@ private:
|
||||
float VPL;
|
||||
};
|
||||
|
||||
union PACKED msgbuffer {
|
||||
union PACKED msgbuffer {
|
||||
msg4007 msg4007u;
|
||||
msg4001 msg4001u;
|
||||
msg4001 msg4001u;
|
||||
uint8_t bytes[128];
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user