mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
DataFlash: consolidate GPS, GPS2 messages
Remove unused dgps_numch, dgps_age from GPS2 Add U field (for use) to both GPS and GPS2
This commit is contained in:
parent
5044189ac9
commit
5776620062
@ -184,24 +184,7 @@ struct PACKED log_GPS {
|
|||||||
uint32_t ground_speed;
|
uint32_t ground_speed;
|
||||||
int32_t ground_course;
|
int32_t ground_course;
|
||||||
float vel_z;
|
float vel_z;
|
||||||
};
|
uint8_t used;
|
||||||
|
|
||||||
struct PACKED log_GPS2 {
|
|
||||||
LOG_PACKET_HEADER;
|
|
||||||
uint64_t time_us;
|
|
||||||
uint8_t status;
|
|
||||||
uint32_t gps_week_ms;
|
|
||||||
uint16_t gps_week;
|
|
||||||
uint8_t num_sats;
|
|
||||||
uint16_t hdop;
|
|
||||||
int32_t latitude;
|
|
||||||
int32_t longitude;
|
|
||||||
int32_t altitude;
|
|
||||||
uint32_t ground_speed;
|
|
||||||
int32_t ground_course;
|
|
||||||
float vel_z;
|
|
||||||
uint8_t dgps_numch;
|
|
||||||
uint32_t dgps_age;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_Message {
|
struct PACKED log_Message {
|
||||||
@ -647,7 +630,7 @@ Format characters in the format string for binary log messages
|
|||||||
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
{ LOG_PARAMETER_MSG, sizeof(log_Parameter), \
|
||||||
"PARM", "QNf", "TimeUS,Name,Value" }, \
|
"PARM", "QNf", "TimeUS,Name,Value" }, \
|
||||||
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
{ LOG_GPS_MSG, sizeof(log_GPS), \
|
||||||
"GPS", "QBIHBcLLeeEef", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,RAlt,Alt,Spd,GCrs,VZ" }, \
|
"GPS", "QBIHBcLLeeEefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,RAlt,Alt,Spd,GCrs,VZ,U" }, \
|
||||||
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
{ LOG_IMU_MSG, sizeof(log_IMU), \
|
||||||
"IMU", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
"IMU", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
||||||
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
{ LOG_MESSAGE_MSG, sizeof(log_Message), \
|
||||||
@ -679,8 +662,8 @@ Format characters in the format string for binary log messages
|
|||||||
|
|
||||||
// messages for more advanced boards
|
// messages for more advanced boards
|
||||||
#define LOG_EXTRA_STRUCTURES \
|
#define LOG_EXTRA_STRUCTURES \
|
||||||
{ LOG_GPS2_MSG, sizeof(log_GPS2), \
|
{ LOG_GPS2_MSG, sizeof(log_GPS), \
|
||||||
"GPS2", "QBIHBcLLeEefBI", "TimeUS,Status,GMS,GWk,NSats,HDp,Lat,Lng,Alt,Spd,GCrs,VZ,DSc,DAg" }, \
|
"GPS2", "QBIHBcLLeeEefB", "TimeUS,Status,GMS,GWk,NSats,HDop,Lat,Lng,RAlt,Alt,Spd,GCrs,VZ,U" }, \
|
||||||
{ LOG_IMU2_MSG, sizeof(log_IMU), \
|
{ LOG_IMU2_MSG, sizeof(log_IMU), \
|
||||||
"IMU2", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
"IMU2", "QffffffIIfBB", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,ErrG,ErrA,Temp,GyHlt,AcHlt" }, \
|
||||||
{ LOG_IMU3_MSG, sizeof(log_IMU), \
|
{ LOG_IMU3_MSG, sizeof(log_IMU), \
|
||||||
@ -783,6 +766,7 @@ enum LogMessages {
|
|||||||
LOG_FORMAT_MSG = 128,
|
LOG_FORMAT_MSG = 128,
|
||||||
LOG_PARAMETER_MSG,
|
LOG_PARAMETER_MSG,
|
||||||
LOG_GPS_MSG,
|
LOG_GPS_MSG,
|
||||||
|
LOG_GPS2_MSG,
|
||||||
LOG_IMU_MSG,
|
LOG_IMU_MSG,
|
||||||
LOG_MESSAGE_MSG,
|
LOG_MESSAGE_MSG,
|
||||||
LOG_RCIN_MSG,
|
LOG_RCIN_MSG,
|
||||||
@ -796,7 +780,6 @@ enum LogMessages {
|
|||||||
LOG_EKF2_MSG,
|
LOG_EKF2_MSG,
|
||||||
LOG_EKF3_MSG,
|
LOG_EKF3_MSG,
|
||||||
LOG_EKF4_MSG,
|
LOG_EKF4_MSG,
|
||||||
LOG_GPS2_MSG,
|
|
||||||
LOG_CMD_MSG,
|
LOG_CMD_MSG,
|
||||||
LOG_RADIO_MSG,
|
LOG_RADIO_MSG,
|
||||||
LOG_ATRP_MSG,
|
LOG_ATRP_MSG,
|
||||||
|
@ -706,49 +706,25 @@ void DataFlash_Class::Log_Write_Parameters(void)
|
|||||||
// Write an GPS packet
|
// Write an GPS packet
|
||||||
void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relative_alt)
|
void DataFlash_Class::Log_Write_GPS(const AP_GPS &gps, uint8_t i, int32_t relative_alt)
|
||||||
{
|
{
|
||||||
if (i == 0) {
|
const struct Location &loc = gps.location(i);
|
||||||
const struct Location &loc = gps.location(i);
|
struct log_GPS pkt = {
|
||||||
struct log_GPS pkt = {
|
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GPS_MSG+i)),
|
||||||
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
|
time_us : hal.scheduler->micros64(),
|
||||||
time_us : hal.scheduler->micros64(),
|
status : (uint8_t)gps.status(i),
|
||||||
status : (uint8_t)gps.status(i),
|
gps_week_ms : gps.time_week_ms(i),
|
||||||
gps_week_ms : gps.time_week_ms(i),
|
gps_week : gps.time_week(i),
|
||||||
gps_week : gps.time_week(i),
|
num_sats : gps.num_sats(i),
|
||||||
num_sats : gps.num_sats(i),
|
hdop : gps.get_hdop(i),
|
||||||
hdop : gps.get_hdop(i),
|
latitude : loc.lat,
|
||||||
latitude : loc.lat,
|
longitude : loc.lng,
|
||||||
longitude : loc.lng,
|
rel_altitude : relative_alt,
|
||||||
rel_altitude : relative_alt,
|
altitude : loc.alt,
|
||||||
altitude : loc.alt,
|
ground_speed : (uint32_t)(gps.ground_speed(i) * 100),
|
||||||
ground_speed : (uint32_t)(gps.ground_speed(i) * 100),
|
ground_course : gps.ground_course_cd(i),
|
||||||
ground_course : gps.ground_course_cd(i),
|
vel_z : gps.velocity(i).z,
|
||||||
vel_z : gps.velocity(i).z,
|
used : (uint8_t)(gps.primary_sensor() == i)
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
|
||||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
|
||||||
if (i > 0) {
|
|
||||||
const struct Location &loc2 = gps.location(i);
|
|
||||||
struct log_GPS2 pkt2 = {
|
|
||||||
LOG_PACKET_HEADER_INIT(LOG_GPS2_MSG),
|
|
||||||
time_us : hal.scheduler->micros64(),
|
|
||||||
status : (uint8_t)gps.status(i),
|
|
||||||
gps_week_ms : gps.time_week_ms(i),
|
|
||||||
gps_week : gps.time_week(i),
|
|
||||||
num_sats : gps.num_sats(i),
|
|
||||||
hdop : gps.get_hdop(i),
|
|
||||||
latitude : loc2.lat,
|
|
||||||
longitude : loc2.lng,
|
|
||||||
altitude : loc2.alt,
|
|
||||||
ground_speed : (uint32_t)(gps.ground_speed(i)*100),
|
|
||||||
ground_course : gps.ground_course_cd(i),
|
|
||||||
vel_z : gps.velocity(i).z,
|
|
||||||
dgps_numch : 0,
|
|
||||||
dgps_age : 0
|
|
||||||
};
|
|
||||||
WriteBlock(&pkt2, sizeof(pkt2));
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write an RCIN packet
|
// Write an RCIN packet
|
||||||
|
Loading…
Reference in New Issue
Block a user