AP_Mission: split logging of mission-upload vs mission-execution
This commit is contained in:
parent
4237a33ce6
commit
163f49827f
@ -17,6 +17,7 @@
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <RC_Channel/RC_Channel_config.h>
|
||||
#include <AC_Fence/AC_Fence.h>
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
const AP_Param::GroupInfo AP_Mission::var_info[] = {
|
||||
|
||||
@ -400,6 +401,15 @@ bool AP_Mission::verify_command(const Mission_Command& cmd)
|
||||
|
||||
bool AP_Mission::start_command(const Mission_Command& cmd)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (log_start_mission_item_bit != (uint32_t)-1) {
|
||||
auto &logger = AP::logger();
|
||||
if (logger.should_log(log_start_mission_item_bit)) {
|
||||
logger.Write_MISE(*this, cmd);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// check for landing related commands and set flags
|
||||
if (is_landing_type_cmd(cmd.id) || cmd.id == MAV_CMD_DO_LAND_START) {
|
||||
_flags.in_landing_sequence = true;
|
||||
|
@ -778,6 +778,10 @@ public:
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
void set_log_start_mission_item_bit(uint32_t bit) { log_start_mission_item_bit = bit; }
|
||||
#endif
|
||||
|
||||
private:
|
||||
static AP_Mission *_singleton;
|
||||
|
||||
@ -949,6 +953,11 @@ private:
|
||||
format to take advantage of new packing
|
||||
*/
|
||||
void format_conversion(uint8_t tag_byte, const Mission_Command &cmd, PackedContent &packed_content) const;
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// if not -1, this bit in LOG_BITMASK specifies whether to log a message each time we start a command:
|
||||
uint32_t log_start_mission_item_bit = -1;
|
||||
#endif
|
||||
};
|
||||
|
||||
namespace AP
|
||||
|
@ -3,11 +3,11 @@
|
||||
#include <AP_Logger/LogStructure.h>
|
||||
|
||||
#define LOG_IDS_FROM_MISSION \
|
||||
LOG_MISE_MSG, \
|
||||
LOG_CMD_MSG
|
||||
|
||||
|
||||
// @LoggerMessage: CMD
|
||||
// @Description: Executed mission command information
|
||||
// @Description: Uploaded mission command information
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: CTot: Total number of mission commands
|
||||
// @Field: CNum: This command's offset in mission
|
||||
@ -36,6 +36,24 @@ struct PACKED log_CMD {
|
||||
uint8_t frame;
|
||||
};
|
||||
|
||||
// @LoggerMessage: MISE
|
||||
// @Description: Executed mission command information; emitted when we start to run an item
|
||||
// @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
|
||||
|
||||
// note we currently reuse the same structure for CMD and MISE.
|
||||
#define LOG_STRUCTURE_FROM_MISSION \
|
||||
{ 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_MISE_MSG, sizeof(log_CMD), \
|
||||
"MISE", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" },
|
||||
|
Loading…
Reference in New Issue
Block a user