mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: update GPS yaw API to add timestamp
This commit is contained in:
parent
f1cbfb3e46
commit
a43bd0ae18
|
@ -57,7 +57,7 @@ void AP_DAL_GPS::start_frame()
|
||||||
|
|
||||||
RGPJ.velocity = gps.velocity(i);
|
RGPJ.velocity = gps.velocity(i);
|
||||||
RGPI.speed_accuracy_returncode = gps.speed_accuracy(i, RGPJ.sacc);
|
RGPI.speed_accuracy_returncode = gps.speed_accuracy(i, RGPJ.sacc);
|
||||||
RGPI.gps_yaw_deg_returncode = gps.gps_yaw_deg(i, RGPJ.yaw_deg, RGPJ.yaw_accuracy_deg);
|
RGPI.gps_yaw_deg_returncode = gps.gps_yaw_deg(i, RGPJ.yaw_deg, RGPJ.yaw_accuracy_deg, RGPJ.yaw_deg_time_ms);
|
||||||
|
|
||||||
WRITE_REPLAY_BLOCK_IFCHANGED(RGPI, RGPI, old_RGPI);
|
WRITE_REPLAY_BLOCK_IFCHANGED(RGPI, RGPI, old_RGPI);
|
||||||
WRITE_REPLAY_BLOCK_IFCHANGED(RGPJ, RGPJ, old_RGPJ);
|
WRITE_REPLAY_BLOCK_IFCHANGED(RGPJ, RGPJ, old_RGPJ);
|
||||||
|
|
|
@ -92,13 +92,10 @@ public:
|
||||||
return speed_accuracy(primary_sensor(), sacc);
|
return speed_accuracy(primary_sensor(), sacc);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool gps_yaw_deg(float &yaw_deg, float &accuracy_deg) const {
|
bool gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const {
|
||||||
return gps_yaw_deg(_RGPH.primary_sensor, yaw_deg, accuracy_deg);
|
|
||||||
}
|
|
||||||
|
|
||||||
bool gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg) const {
|
|
||||||
yaw_deg = _RGPJ[instance].yaw_deg;
|
yaw_deg = _RGPJ[instance].yaw_deg;
|
||||||
accuracy_deg = _RGPJ[instance].yaw_accuracy_deg;
|
accuracy_deg = _RGPJ[instance].yaw_accuracy_deg;
|
||||||
|
time_ms = _RGPJ[instance].yaw_deg_time_ms;
|
||||||
return _RGPI[instance].gps_yaw_deg_returncode;
|
return _RGPI[instance].gps_yaw_deg_returncode;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -208,6 +208,7 @@ struct log_RGPJ {
|
||||||
float sacc;
|
float sacc;
|
||||||
float yaw_deg;
|
float yaw_deg;
|
||||||
float yaw_accuracy_deg;
|
float yaw_accuracy_deg;
|
||||||
|
uint32_t yaw_deg_time_ms;
|
||||||
int32_t lat;
|
int32_t lat;
|
||||||
int32_t lng;
|
int32_t lng;
|
||||||
int32_t alt;
|
int32_t alt;
|
||||||
|
@ -399,7 +400,7 @@ struct log_RBOH {
|
||||||
{ LOG_RGPI_MSG, RLOG_SIZE(RGPI), \
|
{ LOG_RGPI_MSG, RLOG_SIZE(RGPI), \
|
||||||
"RGPI", "ffffBBBB", "OX,OY,OZ,Lg,Flags,Stat,NSats,I", "-------#", "--------" }, \
|
"RGPI", "ffffBBBB", "OX,OY,OZ,Lg,Flags,Stat,NSats,I", "-------#", "--------" }, \
|
||||||
{ LOG_RGPJ_MSG, RLOG_SIZE(RGPJ), \
|
{ LOG_RGPJ_MSG, RLOG_SIZE(RGPJ), \
|
||||||
"RGPJ", "IffffffiiiffHB", "TS,VX,VY,VZ,SA,Y,YA,Lat,Lon,Alt,HA,VA,HD,I", "-------------#", "--------------" }, \
|
"RGPJ", "IffffffIiiiffHB", "TS,VX,VY,VZ,SA,Y,YA,YT,Lat,Lon,Alt,HA,VA,HD,I", "--------------#", "---------------" }, \
|
||||||
{ LOG_RMGH_MSG, RLOG_SIZE(RMGH), \
|
{ LOG_RMGH_MSG, RLOG_SIZE(RMGH), \
|
||||||
"RMGH", "BBfBBBB", "Dec,NumInst,AutoDec,NumEna,LOE,C,FUsable", "-------", "-------" }, \
|
"RMGH", "BBfBBBB", "Dec,NumInst,AutoDec,NumEna,LOE,C,FUsable", "-------", "-------" }, \
|
||||||
{ LOG_RMGI_MSG, RLOG_SIZE(RMGI), \
|
{ LOG_RMGI_MSG, RLOG_SIZE(RMGI), \
|
||||||
|
|
Loading…
Reference in New Issue