AP_GPS_SBF: formatting fixes

This commit is contained in:
Michael Oborne 2015-12-07 21:47:51 +09:00 committed by Randy Mackay
parent f8b0a6a977
commit 0bcc6e324a
2 changed files with 28 additions and 28 deletions

View File

@ -42,10 +42,10 @@ do { \
AP_GPS_SBF::AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state,
AP_HAL::UARTDriver *_port) :
AP_GPS_Backend(_gps, _state, _port)
{
{
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
@ -198,8 +198,8 @@ AP_GPS_SBF::process_message(void)
state.time_week = temp.WNc;
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;
@ -208,19 +208,19 @@ AP_GPS_SBF::process_message(void)
state.velocity.x = (float)(temp.Vn);
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);
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)
@ -277,8 +277,8 @@ AP_GPS_SBF::process_message(void)
const msg4001 &temp = sbf_msg.data.msg4001u;
last_hdop = temp.HDOP;
state.hdop = last_hdop;
state.hdop = last_hdop;
}
return false;

View File

@ -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
@ -104,14 +104,14 @@ private:
uint16_t VDOP;
float HPL;
float VPL;
};
union PACKED msgbuffer {
};
union PACKED msgbuffer {
msg4007 msg4007u;
msg4001 msg4001u;
msg4001 msg4001u;
uint8_t bytes[128];
};
struct sbf_msg_parser_t
{
enum
@ -133,7 +133,7 @@ private:
msgbuffer data;
uint16_t read;
} sbf_msg;
void log_ExtEventPVTGeodetic(const msg4007 &temp);
};