mirror of https://github.com/ArduPilot/ardupilot
Rover: added RC in/out logging
This commit is contained in:
parent
2ce1b14cbb
commit
870ec8a9bb
|
@ -559,7 +559,8 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
|
|||
{ navigate, 5, 1600 },
|
||||
{ update_compass, 5, 2000 },
|
||||
{ update_commands, 5, 1000 },
|
||||
{ update_logging, 5, 1000 },
|
||||
{ update_logging1, 5, 1000 },
|
||||
{ update_logging2, 5, 1000 },
|
||||
{ gcs_retry_deferred, 1, 1000 },
|
||||
{ gcs_update, 1, 1700 },
|
||||
{ gcs_data_stream_send, 1, 3000 },
|
||||
|
@ -706,7 +707,7 @@ static void update_compass(void)
|
|||
/*
|
||||
log some key data - 10Hz
|
||||
*/
|
||||
static void update_logging(void)
|
||||
static void update_logging1(void)
|
||||
{
|
||||
if ((g.log_bitmask & MASK_LOG_ATTITUDE_MED) && !(g.log_bitmask & MASK_LOG_ATTITUDE_FAST))
|
||||
Log_Write_Attitude();
|
||||
|
@ -716,12 +717,21 @@ static void update_logging(void)
|
|||
|
||||
if (g.log_bitmask & MASK_LOG_NTUN)
|
||||
Log_Write_Nav_Tuning();
|
||||
}
|
||||
|
||||
/*
|
||||
log some key data - 10Hz
|
||||
*/
|
||||
static void update_logging2(void)
|
||||
{
|
||||
if (g.log_bitmask & MASK_LOG_STEERING) {
|
||||
if (control_mode == STEERING || control_mode == AUTO || control_mode == RTL || control_mode == GUIDED) {
|
||||
Log_Write_Steering();
|
||||
}
|
||||
}
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_RC)
|
||||
Log_Write_RC();
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -514,6 +514,12 @@ static void Log_Write_Compass()
|
|||
}
|
||||
|
||||
|
||||
static void Log_Write_RC(void)
|
||||
{
|
||||
DataFlash.Log_Write_RCIN();
|
||||
DataFlash.Log_Write_RCOUT();
|
||||
}
|
||||
|
||||
static const struct LogStructure log_structure[] PROGMEM = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
||||
|
@ -587,6 +593,7 @@ static void Log_Write_Mode() {}
|
|||
static void Log_Write_Attitude() {}
|
||||
static void Log_Write_Compass() {}
|
||||
static void start_logging() {}
|
||||
static void Log_Write_RC(void) {}
|
||||
|
||||
#endif // LOGGING_ENABLED
|
||||
|
||||
|
|
|
@ -319,6 +319,7 @@
|
|||
# define LOGGING_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
#define DEFAULT_LOG_BITMASK \
|
||||
MASK_LOG_ATTITUDE_MED | \
|
||||
MASK_LOG_GPS | \
|
||||
|
@ -332,6 +333,10 @@
|
|||
MASK_LOG_CURRENT | \
|
||||
MASK_LOG_STEERING | \
|
||||
MASK_LOG_CAMERA
|
||||
#else
|
||||
// other systems have plenty of space for full logs
|
||||
#define DEFAULT_LOG_BITMASK 0xffff
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
|
|
@ -115,6 +115,7 @@ enum mode {
|
|||
#define MASK_LOG_COMPASS (1<<11)
|
||||
#define MASK_LOG_CAMERA (1<<12)
|
||||
#define MASK_LOG_STEERING (1<<13)
|
||||
#define MASK_LOG_RC (1<<14)
|
||||
|
||||
// Waypoint Modes
|
||||
// ----------------
|
||||
|
|
Loading…
Reference in New Issue