mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduSub: privatize AHRS logging
This commit is contained in:
parent
d605f3aea0
commit
aaa1341b75
@ -178,7 +178,7 @@ void Sub::ten_hz_logging_loop()
|
||||
// log attitude data if we're not already logging at the higher rate
|
||||
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
Log_Write_Attitude();
|
||||
logger.Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
|
||||
ahrs_view.Write_Rate(motors, attitude_control, pos_control);
|
||||
if (should_log(MASK_LOG_PID)) {
|
||||
logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
|
||||
logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
|
||||
@ -212,7 +212,7 @@ void Sub::twentyfive_hz_logging()
|
||||
{
|
||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
Log_Write_Attitude();
|
||||
logger.Write_Rate(&ahrs_view, motors, attitude_control, pos_control);
|
||||
ahrs_view.Write_Rate(motors, attitude_control, pos_control);
|
||||
if (should_log(MASK_LOG_PID)) {
|
||||
logger.Write_PID(LOG_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
|
||||
logger.Write_PID(LOG_PIDP_MSG, attitude_control.get_rate_pitch_pid().get_pid_info());
|
||||
|
@ -55,14 +55,14 @@ void Sub::Log_Write_Attitude()
|
||||
{
|
||||
Vector3f targets = attitude_control.get_att_target_euler_cd();
|
||||
targets.z = wrap_360_cd(targets.z);
|
||||
logger.Write_Attitude(targets);
|
||||
ahrs.Write_Attitude(targets);
|
||||
|
||||
AP::ahrs_navekf().Log_Write();
|
||||
logger.Write_AHRS2();
|
||||
ahrs.Write_AHRS2();
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
sitl.Log_Write_SIMSTATE();
|
||||
#endif
|
||||
logger.Write_POS();
|
||||
ahrs.Write_POS();
|
||||
}
|
||||
|
||||
struct PACKED log_MotBatt {
|
||||
|
Loading…
Reference in New Issue
Block a user