Skip to content

Commit

Permalink
AC_Avoidance: correct defines
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Mar 9, 2024
1 parent b5e7e3e commit ef6dfe2
Showing 1 changed file with 17 additions and 2 deletions.
19 changes: 17 additions & 2 deletions libraries/AC_Avoidance/LogStructure.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@

#include "AC_Avoidance_config.h"

#if AP_AVOIDANCE_ENABLED

#include <AP_Logger/LogStructure.h>

#define LOG_IDS_FROM_AVOIDANCE \
Expand All @@ -12,6 +10,8 @@
LOG_SIMPLE_AVOID_MSG, \
LOG_OD_VISGRAPH_MSG

#if AP_OAPATHPLANNER_BENDYRULER_ENABLED

// @LoggerMessage: OABR
// @Description: Object avoidance (Bendy Ruler) diagnostics
// @Field: TimeUS: Time since system startup
Expand Down Expand Up @@ -45,7 +45,9 @@ struct PACKED log_OABendyRuler {
int32_t oa_lng;
int32_t oa_alt;
};
#endif // AP_OAPATHPLANNER_BENDYRULER_ENABLED

#if AP_OAPATHPLANNER_DIJKSTRA_ENABLED
// @LoggerMessage: OADJ
// @Description: Object avoidance (Dijkstra) diagnostics
// @Field: TimeUS: Time since system startup
Expand All @@ -69,7 +71,9 @@ struct PACKED log_OADijkstra {
int32_t oa_lat;
int32_t oa_lng;
};
#endif // AP_OAPATHPLANNER_DIJKSTRA_ENABLED

#if AP_AVOIDANCE_ENABLED
// @LoggerMessage: SA
// @Description: Simple Avoidance messages
// @Field: TimeUS: Time since system startup
Expand All @@ -93,7 +97,9 @@ struct PACKED log_SimpleAvoid {
float modified_vel_z;
uint8_t backing_up;
};
#endif // AP_AVOIDANCE_ENABLED

#if AC_OAPATHPLANNER_ENABLED
// @LoggerMessage: OAVG
// @Description: Object avoidance path planning visgraph points
// @Field: TimeUS: Time since system startup
Expand All @@ -109,16 +115,25 @@ struct PACKED log_OD_Visgraph {
int32_t Lat;
int32_t Lon;
};
#endif // AP_OAPATHPLANNER_ENABLED

#define LOG_STRUCTURE_FROM_AVOIDANCE \
#if AP_OAPATHPLANNER_BENDYRULER_ENABLED
{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \
"OABR","QBBHHHBfLLiLLi","TimeUS,Type,Act,DYaw,Yaw,DP,RChg,Mar,DLt,DLg,DAlt,OLt,OLg,OAlt", "s--ddd-mDUmDUm", "F-------GGBGGB" , true }, \
#endif
#if AP_OAPATHPLANNER_DIJKSTRA_ENABLED
{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \
"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "s----DUDU", "F----GGGG" , true }, \
#endif
#if AP_AVOIDANCE_ENABLED
{ LOG_SIMPLE_AVOID_MSG, sizeof(log_SimpleAvoid), \
"SA", "QBffffffB","TimeUS,State,DVelX,DVelY,DVelZ,MVelX,MVelY,MVelZ,Back", "s-nnnnnn-", "F--------", true }, \
#endif
#if AC_OAPATHPLANNER_ENABLED
{ LOG_OD_VISGRAPH_MSG, sizeof(log_OD_Visgraph), \
"OAVG", "QBBLL", "TimeUS,version,point_num,Lat,Lon", "s--DU", "F--GG", true},
#endif

#else

Expand Down

0 comments on commit ef6dfe2

Please sign in to comment.