AP_Logger: move logging of Beacon into Beacon library

This commit is contained in:
Peter Barker 2022-03-04 12:31:25 +11:00 committed by Peter Barker
parent bbcf0a0968
commit e5c40d0e54
3 changed files with 3 additions and 59 deletions

View File

@ -58,7 +58,6 @@
#include <AP_Logger/LogStructure.h>
#include <AP_Motors/AP_Motors.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_Beacon/AP_Beacon.h>
#include <AP_Vehicle/ModeReason.h>
#include <stdint.h>
@ -306,7 +305,6 @@ public:
void Write_RallyPoint(uint8_t total,
uint8_t sequence,
const RallyLocation &rally_point);
void Write_Beacon(AP_Beacon &beacon);
void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point);
void Write_Winch(bool healthy, bool thread_end, bool moving, bool clutch, uint8_t mode, float desired_length, float length, float desired_rate, uint16_t tension, float voltage, int8_t temp);
void Write_PSCN(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel);

View File

@ -426,33 +426,6 @@ void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info)
WriteBlock(&pkt, sizeof(pkt));
}
// Write beacon sensor (position) data
void AP_Logger::Write_Beacon(AP_Beacon &beacon)
{
if (!beacon.enabled()) {
return;
}
// position
Vector3f pos;
float accuracy = 0.0f;
beacon.get_vehicle_position_ned(pos, accuracy);
const struct log_Beacon pkt_beacon{
LOG_PACKET_HEADER_INIT(LOG_BEACON_MSG),
time_us : AP_HAL::micros64(),
health : (uint8_t)beacon.healthy(),
count : (uint8_t)beacon.count(),
dist0 : beacon.beacon_distance(0),
dist1 : beacon.beacon_distance(1),
dist2 : beacon.beacon_distance(2),
dist3 : beacon.beacon_distance(3),
posx : pos.x,
posy : pos.y,
posz : pos.z
};
WriteBlock(&pkt_beacon, sizeof(pkt_beacon));
}
void AP_Logger::Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& breadcrumb)
{
const struct log_SRTL pkt_srtl{

View File

@ -120,6 +120,7 @@ const struct MultiplierStructure log_Multipliers[] = {
#define HEAD_BYTE1 0xA3 // Decimal 163
#define HEAD_BYTE2 0x95 // Decimal 149
#include <AP_Beacon/LogStructure.h>
#include <AP_DAL/LogStructure.h>
#include <AP_NavEKF2/LogStructure.h>
#include <AP_NavEKF3/LogStructure.h>
@ -514,20 +515,6 @@ struct PACKED log_Rally {
int16_t altitude;
};
struct PACKED log_Beacon {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t health;
uint8_t count;
float dist0;
float dist1;
float dist2;
float dist3;
float posx;
float posy;
float posz;
};
struct PACKED log_Performance {
LOG_PACKET_HEADER;
uint64_t time_us;
@ -738,19 +725,6 @@ struct PACKED log_VER {
// @Field: Hp: Probability sensor is healthy
// @Field: Pri: True if sensor is the primary sensor
// @LoggerMessage: BCN
// @Description: Beacon information
// @Field: TimeUS: Time since system startup
// @Field: Health: True if beacon sensor is healthy
// @Field: Cnt: Number of beacons being used
// @Field: D0: Distance to first beacon
// @Field: D1: Distance to second beacon
// @Field: D2: Distance to third beacon
// @Field: D3: Distance to fourth beacon
// @Field: PosX: Calculated beacon position, x-axis
// @Field: PosY: Calculated beacon position, y-axis
// @Field: PosZ: Calculated beacon position, z-axis
// @LoggerMessage: CMD
// @Description: Executed mission command information
// @Field: TimeUS: Time since system startup
@ -1230,8 +1204,7 @@ LOG_STRUCTURE_FROM_CAMERA \
"RFND", "QBCBB", "TimeUS,Instance,Dist,Stat,Orient", "s#m--", "F-B--", true }, \
{ LOG_MAV_STATS, sizeof(log_MAV_Stats), \
"DMS", "QIIIIBBBBBBBBB", "TimeUS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s-------------", "F-------------" }, \
{ LOG_BEACON_MSG, sizeof(log_Beacon), \
"BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--0000000", true }, \
LOG_STRUCTURE_FROM_BEACON \
LOG_STRUCTURE_FROM_PROXIMITY \
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), \
"PM", "QHHIIHHIIIIII", "TimeUS,NLon,NLoop,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex", "s---b%------s", "F---0A------F" }, \
@ -1365,7 +1338,7 @@ enum LogMessages : uint8_t {
LOG_IDS_FROM_VISUALODOM,
LOG_IDS_FROM_AVOIDANCE,
LOG_BEACON_MSG,
LOG_IDS_FROM_BEACON,
LOG_IDS_FROM_PROXIMITY,
LOG_DF_FILE_STATS,
LOG_SRTL_MSG,