mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
Rover: DFMessageWriter; ability to trickle messages out to DF
This commit is contained in:
parent
51a761656e
commit
6e3687f8af
@ -80,6 +80,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] PROGMEM = {
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
SCHED_TASK(frsky_telemetry_send, 10, 100),
|
||||
#endif
|
||||
SCHED_TASK(dataflash_periodic, 1, 300),
|
||||
};
|
||||
|
||||
/*
|
||||
@ -319,6 +320,11 @@ void Rover::one_second_loop(void)
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
}
|
||||
|
||||
void Rover::dataflash_periodic(void)
|
||||
{
|
||||
DataFlash.periodic_tasks();
|
||||
}
|
||||
|
||||
void Rover::update_GPS_50Hz(void)
|
||||
{
|
||||
static uint32_t last_gps_reading[GPS_MAX_INSTANCES];
|
||||
|
@ -215,7 +215,8 @@ struct PACKED log_Startup {
|
||||
uint16_t command_total;
|
||||
};
|
||||
|
||||
void Rover::Log_Write_Startup(uint8_t type)
|
||||
// do not add any extra log writes to this function; see LogStartup.cpp
|
||||
bool Rover::Log_Write_Startup(uint8_t type)
|
||||
{
|
||||
struct log_Startup pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
|
||||
@ -223,12 +224,7 @@ void Rover::Log_Write_Startup(uint8_t type)
|
||||
startup_type : type,
|
||||
command_total : mission.num_commands()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
|
||||
// write all commands to the dataflash as well
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
DataFlash.Log_Write_EntireMission(mission);
|
||||
}
|
||||
return DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
struct PACKED log_Control_Tuning {
|
||||
@ -423,12 +419,21 @@ void Rover::Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
|
||||
}
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
void Rover::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
// only 200(?) bytes are guaranteed by DataFlash
|
||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||
}
|
||||
|
||||
// start a new log
|
||||
void Rover::start_logging()
|
||||
{
|
||||
in_mavlink_delay = true;
|
||||
DataFlash.set_mission(&mission);
|
||||
DataFlash.setVehicle_Startup_Log_Writer(
|
||||
FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void)
|
||||
);
|
||||
DataFlash.StartNewLog();
|
||||
DataFlash.Log_Write_SysInfo(PSTR(FIRMWARE_STRING));
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
|
||||
|
@ -135,7 +135,7 @@ private:
|
||||
RC_Channel *channel_throttle;
|
||||
RC_Channel *channel_learn;
|
||||
|
||||
DataFlash_Class DataFlash;
|
||||
DataFlash_Class DataFlash{FIRMWARE_STRING};
|
||||
|
||||
bool in_log_download;
|
||||
|
||||
@ -402,10 +402,11 @@ private:
|
||||
void gcs_update(void);
|
||||
void gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str);
|
||||
void gcs_retry_deferred(void);
|
||||
|
||||
void do_erase_logs(void);
|
||||
void Log_Write_Performance();
|
||||
void Log_Write_Steering();
|
||||
void Log_Write_Startup(uint8_t type);
|
||||
bool Log_Write_Startup(uint8_t type);
|
||||
void Log_Write_Control_Tuning();
|
||||
void Log_Write_Nav_Tuning();
|
||||
void Log_Write_Sonar();
|
||||
@ -414,9 +415,11 @@ private:
|
||||
void Log_Write_RC(void);
|
||||
void Log_Write_Baro(void);
|
||||
void Log_Write_Home_And_Origin();
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page);
|
||||
void log_init(void);
|
||||
void start_logging() ;
|
||||
|
||||
void load_parameters(void);
|
||||
void throttle_slew_limit(int16_t last_throttle);
|
||||
bool auto_check_trigger(void);
|
||||
@ -533,6 +536,8 @@ public:
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
int8_t test_shell(uint8_t argc, const Menu::arg *argv);
|
||||
#endif
|
||||
|
||||
void dataflash_periodic(void);
|
||||
};
|
||||
|
||||
#define MENU_FUNC(func) FUNCTOR_BIND(&rover, &Rover::func, int8_t, uint8_t, const Menu::arg *)
|
||||
|
@ -213,7 +213,6 @@ void Rover::init_ardupilot()
|
||||
init_capabilities();
|
||||
|
||||
startup_ground();
|
||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||
|
||||
set_mode((enum mode)g.initial_mode.get());
|
||||
|
||||
@ -511,11 +510,7 @@ bool Rover::should_log(uint32_t mask)
|
||||
}
|
||||
bool ret = hal.util->get_soft_armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0;
|
||||
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
||||
// we have to set in_mavlink_delay to prevent logging while
|
||||
// writing headers
|
||||
in_mavlink_delay = true;
|
||||
start_logging();
|
||||
in_mavlink_delay = false;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user