mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Logger: log source sysid/compid in MAVC
For field length purposed had tor remove Current and autocontinue which we don't care about anyway.
This commit is contained in:
parent
ec53a41ffd
commit
13a7b60279
@ -317,7 +317,11 @@ public:
|
|||||||
void Write_Mode(uint8_t mode, const ModeReason reason);
|
void Write_Mode(uint8_t mode, const ModeReason reason);
|
||||||
|
|
||||||
void Write_EntireMission();
|
void Write_EntireMission();
|
||||||
void Write_Command(const mavlink_command_int_t &packet, MAV_RESULT result, bool was_command_long=false);
|
void Write_Command(const mavlink_command_int_t &packet,
|
||||||
|
uint8_t source_system,
|
||||||
|
uint8_t source_component,
|
||||||
|
MAV_RESULT result,
|
||||||
|
bool was_command_long=false);
|
||||||
void Write_Mission_Cmd(const AP_Mission &mission,
|
void Write_Mission_Cmd(const AP_Mission &mission,
|
||||||
const AP_Mission::Mission_Command &cmd);
|
const AP_Mission::Mission_Command &cmd);
|
||||||
void Write_RPM(const AP_RPM &rpm_sensor);
|
void Write_RPM(const AP_RPM &rpm_sensor);
|
||||||
|
@ -217,6 +217,8 @@ void AP_Logger::Write_RSSI()
|
|||||||
}
|
}
|
||||||
|
|
||||||
void AP_Logger::Write_Command(const mavlink_command_int_t &packet,
|
void AP_Logger::Write_Command(const mavlink_command_int_t &packet,
|
||||||
|
uint8_t source_system,
|
||||||
|
uint8_t source_component,
|
||||||
const MAV_RESULT result,
|
const MAV_RESULT result,
|
||||||
bool was_command_long)
|
bool was_command_long)
|
||||||
{
|
{
|
||||||
@ -225,10 +227,10 @@ void AP_Logger::Write_Command(const mavlink_command_int_t &packet,
|
|||||||
time_us : AP_HAL::micros64(),
|
time_us : AP_HAL::micros64(),
|
||||||
target_system : packet.target_system,
|
target_system : packet.target_system,
|
||||||
target_component: packet.target_component,
|
target_component: packet.target_component,
|
||||||
|
source_system : source_system,
|
||||||
|
source_component: source_component,
|
||||||
frame : packet.frame,
|
frame : packet.frame,
|
||||||
command : packet.command,
|
command : packet.command,
|
||||||
current : packet.current,
|
|
||||||
autocontinue : packet.autocontinue,
|
|
||||||
param1 : packet.param1,
|
param1 : packet.param1,
|
||||||
param2 : packet.param2,
|
param2 : packet.param2,
|
||||||
param3 : packet.param3,
|
param3 : packet.param3,
|
||||||
|
@ -336,10 +336,10 @@ struct PACKED log_MAVLink_Command {
|
|||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
uint8_t target_system;
|
uint8_t target_system;
|
||||||
uint8_t target_component;
|
uint8_t target_component;
|
||||||
|
uint8_t source_system;
|
||||||
|
uint8_t source_component;
|
||||||
uint8_t frame;
|
uint8_t frame;
|
||||||
uint16_t command;
|
uint16_t command;
|
||||||
uint8_t current;
|
|
||||||
uint8_t autocontinue;
|
|
||||||
float param1;
|
float param1;
|
||||||
float param2;
|
float param2;
|
||||||
float param3;
|
float param3;
|
||||||
@ -908,10 +908,10 @@ struct PACKED log_PSCZ {
|
|||||||
// @Field: TimeUS: Time since system startup
|
// @Field: TimeUS: Time since system startup
|
||||||
// @Field: TS: target system for command
|
// @Field: TS: target system for command
|
||||||
// @Field: TC: target component for command
|
// @Field: TC: target component for command
|
||||||
|
// @Field: SS: target system for command
|
||||||
|
// @Field: SC: target component for command
|
||||||
// @Field: Fr: command frame
|
// @Field: Fr: command frame
|
||||||
// @Field: Cmd: mavlink command enum value
|
// @Field: Cmd: mavlink command enum value
|
||||||
// @Field: Cur: current flag from mavlink packet
|
|
||||||
// @Field: AC: autocontinue flag from mavlink packet
|
|
||||||
// @Field: P1: first parameter from mavlink packet
|
// @Field: P1: first parameter from mavlink packet
|
||||||
// @Field: P2: second parameter from mavlink packet
|
// @Field: P2: second parameter from mavlink packet
|
||||||
// @Field: P3: third parameter from mavlink packet
|
// @Field: P3: third parameter from mavlink packet
|
||||||
@ -1249,7 +1249,7 @@ LOG_STRUCTURE_FROM_PRECLAND \
|
|||||||
{ LOG_CMD_MSG, sizeof(log_Cmd), \
|
{ LOG_CMD_MSG, sizeof(log_Cmd), \
|
||||||
"CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \
|
"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", "QBBBHBBffffiifBB","TimeUS,TS,TC,Fr,Cmd,Cur,AC,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), \
|
||||||
"RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------", true }, \
|
"RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------", true }, \
|
||||||
LOG_STRUCTURE_FROM_CAMERA \
|
LOG_STRUCTURE_FROM_CAMERA \
|
||||||
|
Loading…
Reference in New Issue
Block a user