mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Logger: move Mission log structures into Mission library
This commit is contained in:
parent
bdecbb5369
commit
b98e682ec6
@ -304,7 +304,7 @@ bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission,
|
|||||||
{
|
{
|
||||||
mavlink_mission_item_int_t mav_cmd = {};
|
mavlink_mission_item_int_t mav_cmd = {};
|
||||||
AP_Mission::mission_cmd_to_mavlink_int(cmd,mav_cmd);
|
AP_Mission::mission_cmd_to_mavlink_int(cmd,mav_cmd);
|
||||||
const struct log_Cmd pkt{
|
const struct log_CMD pkt{
|
||||||
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
|
||||||
time_us : AP_HAL::micros64(),
|
time_us : AP_HAL::micros64(),
|
||||||
command_total : mission.num_commands(),
|
command_total : mission.num_commands(),
|
||||||
|
@ -146,6 +146,7 @@ const struct MultiplierStructure log_Multipliers[] = {
|
|||||||
#include <AP_Landing/LogStructure.h>
|
#include <AP_Landing/LogStructure.h>
|
||||||
#include <AC_AttitudeControl/LogStructure.h>
|
#include <AC_AttitudeControl/LogStructure.h>
|
||||||
#include <AP_HAL/LogStructure.h>
|
#include <AP_HAL/LogStructure.h>
|
||||||
|
#include <AP_Mission/LogStructure.h>
|
||||||
|
|
||||||
// structure used to define logging format
|
// structure used to define logging format
|
||||||
// It is packed on ChibiOS to save flash space; however, this causes problems
|
// It is packed on ChibiOS to save flash space; however, this causes problems
|
||||||
@ -350,22 +351,6 @@ struct PACKED log_MCU {
|
|||||||
float MCU_voltage_max;
|
float MCU_voltage_max;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_Cmd {
|
|
||||||
LOG_PACKET_HEADER;
|
|
||||||
uint64_t time_us;
|
|
||||||
uint16_t command_total;
|
|
||||||
uint16_t sequence;
|
|
||||||
uint16_t command;
|
|
||||||
float param1;
|
|
||||||
float param2;
|
|
||||||
float param3;
|
|
||||||
float param4;
|
|
||||||
int32_t latitude;
|
|
||||||
int32_t longitude;
|
|
||||||
float altitude;
|
|
||||||
uint8_t frame;
|
|
||||||
};
|
|
||||||
|
|
||||||
struct PACKED log_MAVLink_Command {
|
struct PACKED log_MAVLink_Command {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
@ -712,21 +697,6 @@ struct PACKED log_VER {
|
|||||||
// @Field: TR: innovation test ratio
|
// @Field: TR: innovation test ratio
|
||||||
// @Field: Pri: True if sensor is the primary sensor
|
// @Field: Pri: True if sensor is the primary sensor
|
||||||
|
|
||||||
// @LoggerMessage: CMD
|
|
||||||
// @Description: Executed mission command information
|
|
||||||
// @Field: TimeUS: Time since system startup
|
|
||||||
// @Field: CTot: Total number of mission commands
|
|
||||||
// @Field: CNum: This command's offset in mission
|
|
||||||
// @Field: CId: Command type
|
|
||||||
// @Field: Prm1: Parameter 1
|
|
||||||
// @Field: Prm2: Parameter 2
|
|
||||||
// @Field: Prm3: Parameter 3
|
|
||||||
// @Field: Prm4: Parameter 4
|
|
||||||
// @Field: Lat: Command latitude
|
|
||||||
// @Field: Lng: Command longitude
|
|
||||||
// @Field: Alt: Command altitude
|
|
||||||
// @Field: Frame: Frame used for position
|
|
||||||
|
|
||||||
// @LoggerMessage: CSRV
|
// @LoggerMessage: CSRV
|
||||||
// @Description: Servo feedback data
|
// @Description: Servo feedback data
|
||||||
// @Field: TimeUS: Time since system startup
|
// @Field: TimeUS: Time since system startup
|
||||||
@ -1218,8 +1188,7 @@ LOG_STRUCTURE_FROM_PRECLAND \
|
|||||||
"POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---", true }, \
|
"POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---", true }, \
|
||||||
{ LOG_MCU_MSG, sizeof(log_MCU), \
|
{ LOG_MCU_MSG, sizeof(log_MCU), \
|
||||||
"MCU","Qffff","TimeUS,MTemp,MVolt,MVmin,MVmax", "sOvvv", "F0000", true }, \
|
"MCU","Qffff","TimeUS,MTemp,MVolt,MVmin,MVmax", "sOvvv", "F0000", true }, \
|
||||||
{ LOG_CMD_MSG, sizeof(log_Cmd), \
|
LOG_STRUCTURE_FROM_MISSION \
|
||||||
"CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \
|
|
||||||
{ LOG_MAVLINK_COMMAND_MSG, sizeof(log_MAVLink_Command), \
|
{ LOG_MAVLINK_COMMAND_MSG, sizeof(log_MAVLink_Command), \
|
||||||
"MAVC", "QBBBBBHffffiifBB","TimeUS,TS,TC,SS,SC,Fr,Cmd,P1,P2,P3,P4,X,Y,Z,Res,WL", "s---------------", "F---------------" }, \
|
"MAVC", "QBBBBBHffffiifBB","TimeUS,TS,TC,SS,SC,Fr,Cmd,P1,P2,P3,P4,X,Y,Z,Res,WL", "s---------------", "F---------------" }, \
|
||||||
{ LOG_RADIO_MSG, sizeof(log_Radio), \
|
{ LOG_RADIO_MSG, sizeof(log_Radio), \
|
||||||
@ -1326,7 +1295,6 @@ enum LogMessages : uint8_t {
|
|||||||
LOG_MCU_MSG,
|
LOG_MCU_MSG,
|
||||||
LOG_IDS_FROM_AHRS,
|
LOG_IDS_FROM_AHRS,
|
||||||
LOG_SIMSTATE_MSG,
|
LOG_SIMSTATE_MSG,
|
||||||
LOG_CMD_MSG,
|
|
||||||
LOG_MAVLINK_COMMAND_MSG,
|
LOG_MAVLINK_COMMAND_MSG,
|
||||||
LOG_RADIO_MSG,
|
LOG_RADIO_MSG,
|
||||||
LOG_ATRP_MSG,
|
LOG_ATRP_MSG,
|
||||||
@ -1337,6 +1305,7 @@ enum LogMessages : uint8_t {
|
|||||||
LOG_IDS_FROM_ESC_TELEM,
|
LOG_IDS_FROM_ESC_TELEM,
|
||||||
LOG_IDS_FROM_BATTMONITOR,
|
LOG_IDS_FROM_BATTMONITOR,
|
||||||
LOG_IDS_FROM_HAL_CHIBIOS,
|
LOG_IDS_FROM_HAL_CHIBIOS,
|
||||||
|
LOG_IDS_FROM_MISSION,
|
||||||
|
|
||||||
LOG_IDS_FROM_GPS,
|
LOG_IDS_FROM_GPS,
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user