mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Logger: add error code to Write_OADijkstra
This commit is contained in:
parent
a0c6ff95e4
commit
3431938bce
@ -273,7 +273,7 @@ public:
|
||||
void Write_Proximity(AP_Proximity &proximity);
|
||||
void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
|
||||
void Write_OABendyRuler(bool active, float target_yaw, float margin, const Location &final_dest, const Location &oa_dest);
|
||||
void Write_OADijkstra(uint8_t state, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest);
|
||||
void Write_OADijkstra(uint8_t state, uint8_t error_id, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest);
|
||||
|
||||
void Write(const char *name, const char *labels, const char *fmt, ...);
|
||||
void Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);
|
||||
|
@ -988,12 +988,13 @@ void AP_Logger::Write_OABendyRuler(bool active, float target_yaw, float margin,
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void AP_Logger::Write_OADijkstra(uint8_t state, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest)
|
||||
void AP_Logger::Write_OADijkstra(uint8_t state, uint8_t error_id, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest)
|
||||
{
|
||||
struct log_OADijkstra pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_OA_DIJKSTRA_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
state : state,
|
||||
error_id : error_id,
|
||||
curr_point : curr_point,
|
||||
tot_points : tot_points,
|
||||
final_lat : final_dest.lat,
|
||||
|
@ -1169,6 +1169,7 @@ struct PACKED log_OADijkstra {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint8_t state;
|
||||
uint8_t error_id;
|
||||
uint8_t curr_point;
|
||||
uint8_t tot_points;
|
||||
int32_t final_lat;
|
||||
@ -1395,7 +1396,7 @@ struct PACKED log_Arm_Disarm {
|
||||
{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \
|
||||
"OABR","QBHHfLLLL","TimeUS,Active,DesYaw,Yaw,Mar,DLat,DLng,OALat,OALng", "sbddmDUDU", "F----GGGG" }, \
|
||||
{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \
|
||||
"OADJ","QBBBLLLL","TimeUS,State,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbDUDU", "F---GGGG" }
|
||||
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "sbbbbDUDU", "F----GGGG" }
|
||||
|
||||
// messages for more advanced boards
|
||||
#define LOG_EXTRA_STRUCTURES \
|
||||
|
Loading…
Reference in New Issue
Block a user