Path: blob/master/libraries/AC_Avoidance/LogStructure.h
4182 views
#pragma once12#include <AP_Logger/LogStructure.h>3#include "AC_Avoidance_config.h"45#define LOG_IDS_FROM_AVOIDANCE \6LOG_OA_BENDYRULER_MSG, \7LOG_OA_DIJKSTRA_MSG, \8LOG_SIMPLE_AVOID_MSG, \9LOG_OD_VISGRAPH_MSG1011// @LoggerMessage: OABR12// @Description: Object avoidance (Bendy Ruler) diagnostics13// @Field: TimeUS: Time since system startup14// @Field: Type: Type of BendyRuler currently active15// @Field: Act: True if Bendy Ruler avoidance is being used16// @Field: DYaw: Best yaw chosen to avoid obstacle17// @Field: Yaw: Current vehicle yaw18// @Field: DP: Desired pitch chosen to avoid obstacle19// @Field: RChg: True if BendyRuler resisted changing bearing and continued in last calculated bearing20// @Field: Mar: Margin from path to obstacle on best yaw chosen21// @Field: DLt: Destination latitude22// @Field: DLg: Destination longitude23// @Field: DAlt: Desired alt above EKF Origin24// @Field: OLt: Intermediate location chosen for avoidance25// @Field: OLg: Intermediate location chosen for avoidance26// @Field: OAlt: Intermediate alt chosen for avoidance above EKF origin27struct PACKED log_OABendyRuler {28LOG_PACKET_HEADER;29uint64_t time_us;30uint8_t type;31uint8_t active;32uint16_t target_yaw;33uint16_t yaw;34uint16_t target_pitch;35bool resist_chg;36float margin;37int32_t final_lat;38int32_t final_lng;39float final_alt;40int32_t oa_lat;41int32_t oa_lng;42float oa_alt;43};4445// @LoggerMessage: OADJ46// @Description: Object avoidance (Dijkstra) diagnostics47// @Field: TimeUS: Time since system startup48// @Field: State: Dijkstra avoidance library state49// @Field: Err: Dijkstra library error condition50// @Field: CurrPoint: Destination point in calculated path to destination51// @Field: TotPoints: Number of points in path to destination52// @Field: DLat: Destination latitude53// @Field: DLng: Destination longitude54// @Field: OALat: Object Avoidance chosen destination point latitude55// @Field: OALng: Object Avoidance chosen destination point longitude56struct PACKED log_OADijkstra {57LOG_PACKET_HEADER;58uint64_t time_us;59uint8_t state;60uint8_t error_id;61uint8_t curr_point;62uint8_t tot_points;63int32_t final_lat;64int32_t final_lng;65int32_t oa_lat;66int32_t oa_lng;67};6869// @LoggerMessage: SA70// @Description: Simple Avoidance messages71// @Field: TimeUS: Time since system startup72// @Field: State: True if Simple Avoidance is active73// @Field: DVelX: Desired velocity, X-Axis (Velocity before Avoidance)74// @Field: DVelY: Desired velocity, Y-Axis (Velocity before Avoidance)75// @Field: DVelZ: Desired velocity, Z-Axis (Velocity before Avoidance)76// @Field: MVelX: Modified velocity, X-Axis (Velocity after Avoidance)77// @Field: MVelY: Modified velocity, Y-Axis (Velocity after Avoidance)78// @Field: MVelZ: Modified velocity, Z-Axis (Velocity after Avoidance)79// @Field: Back: True if vehicle is backing away80struct PACKED log_SimpleAvoid {81LOG_PACKET_HEADER;82uint64_t time_us;83uint8_t state;84float desired_vel_x;85float desired_vel_y;86float desired_vel_z;87float modified_vel_x;88float modified_vel_y;89float modified_vel_z;90uint8_t backing_up;91};9293// @LoggerMessage: OAVG94// @Description: Object avoidance path planning visgraph points95// @Field: TimeUS: Time since system startup96// @Field: version: Visgraph version, increments each time the visgraph is re-generated97// @Field: point_num: point number in visgraph98// @Field: Lat: Latitude99// @Field: Lon: longitude100struct PACKED log_OD_Visgraph {101LOG_PACKET_HEADER;102uint64_t time_us;103uint8_t version;104uint8_t point_num;105int32_t Lat;106int32_t Lon;107};108109#if AP_AVOIDANCE_ENABLED110#define LOG_STRUCTURE_FROM_AVOIDANCE \111{ LOG_OA_BENDYRULER_MSG, sizeof(log_OABendyRuler), \112"OABR","QBBHHHBfLLfLLf","TimeUS,Type,Act,DYaw,Yaw,DP,RChg,Mar,DLt,DLg,DAlt,OLt,OLg,OAlt", "s--ddd-mDUmDUm", "F-------GG0GG0" , true }, \113{ LOG_OA_DIJKSTRA_MSG, sizeof(log_OADijkstra), \114"OADJ","QBBBBLLLL","TimeUS,State,Err,CurrPoint,TotPoints,DLat,DLng,OALat,OALng", "s----DUDU", "F----GGGG" , true }, \115{ LOG_SIMPLE_AVOID_MSG, sizeof(log_SimpleAvoid), \116"SA", "QBffffffB","TimeUS,State,DVelX,DVelY,DVelZ,MVelX,MVelY,MVelZ,Back", "s-nnnnnn-", "F--------", true }, \117{ LOG_OD_VISGRAPH_MSG, sizeof(log_OD_Visgraph), \118"OAVG", "QBBLL", "TimeUS,version,point_num,Lat,Lon", "s--DU", "F--GG", true},119#else120#define LOG_STRUCTURE_FROM_AVOIDANCE121#endif // AP_AVOIDANCE_ENABLED122123124