mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Sub: log ANG attitude message
This commit is contained in:
parent
2e194383d2
commit
3bbf4e6b33
@ -183,6 +183,7 @@ void Sub::ten_hz_logging_loop()
|
|||||||
// log attitude data if we're not already logging at the higher rate
|
// 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)) {
|
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
|
attitude_control.Write_ANG();
|
||||||
attitude_control.Write_Rate(pos_control);
|
attitude_control.Write_Rate(pos_control);
|
||||||
if (should_log(MASK_LOG_PID)) {
|
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_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
|
||||||
@ -222,6 +223,7 @@ void Sub::twentyfive_hz_logging()
|
|||||||
{
|
{
|
||||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
|
attitude_control.Write_ANG();
|
||||||
attitude_control.Write_Rate(pos_control);
|
attitude_control.Write_Rate(pos_control);
|
||||||
if (should_log(MASK_LOG_PID)) {
|
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_PIDR_MSG, attitude_control.get_rate_roll_pid().get_pid_info());
|
||||||
|
Loading…
Reference in New Issue
Block a user