Skip to content

Commit

Permalink
Copter: provide more options around attitude rates
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Jun 6, 2024
1 parent f0efd09 commit 1e7d0af
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 7 deletions.
12 changes: 9 additions & 3 deletions ArduCopter/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,14 @@ void Copter::rate_controller_thread()
uint32_t last_timing_msg_us = 0;
#endif

uint8_t filter_rate_decimate = uint8_t((ins.get_raw_gyro_rate_hz() + copter.g2.att_filter_rate_hz - 1) / copter.g2.att_filter_rate_hz);
uint8_t log_rate_decimate = uint8_t((ins.get_raw_gyro_rate_hz() + copter.g2.att_log_rate_hz - 1) / copter.g2.att_log_rate_hz);
uint8_t filter_rate_decimate = 2;
if (copter.g2.att_filter_rate_hz != 0) {
filter_rate_decimate = uint8_t((ins.get_raw_gyro_rate_hz() + copter.g2.att_filter_rate_hz - 1) / copter.g2.att_filter_rate_hz);
}
uint8_t log_rate_decimate = 0;
if (copter.g2.att_log_rate_hz != 0) {
log_rate_decimate = uint8_t((ins.get_raw_gyro_rate_hz() + copter.g2.att_log_rate_hz - 1) / copter.g2.att_log_rate_hz);
}
uint8_t filter_loop_count = 0;
uint8_t log_loop_count = 0;

Expand Down Expand Up @@ -143,7 +149,7 @@ void Copter::rate_controller_thread()
}

// fast logging output
if (log_loop_count++ >= log_rate_decimate) {
if (log_rate_decimate > 0 && log_loop_count++ >= log_rate_decimate) {
log_loop_count = 0;
#if HAL_LOGGING_ENABLED
fast_logging();
Expand Down
4 changes: 3 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -522,9 +522,11 @@ void Copter::update_batt_compass(void)
// should be run at loop rate
void Copter::loop_rate_logging()
{
if (using_rate_thread) {
#if AP_INERTIALSENSOR_RATE_LOOP_WINDOW_ENABLED
if (using_rate_thread && copter.g2.att_log_rate_hz != 0) {
return;
}
#endif

fast_logging();
}
Expand Down
6 changes: 3 additions & 3 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1231,16 +1231,16 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = {
#if AP_INERTIALSENSOR_RATE_LOOP_WINDOW_ENABLED
// @Param: ATT_FILTER_RATE
// @DisplayName: Rate thread notch update rate
// @Description: The rate of rate thread filter updates in Hz. The actual rate is constrained to be a whole divisor of the gyro rate and thus cannot be larger than the gyro rate.
// @Description: The rate of rate thread filter updates in Hz. The actual rate is constrained to be a whole divisor of the gyro rate and thus cannot be larger than the gyro rate. A value of 0 will utilize a rate of half the attitude update rate (usually the gyro rate).
// @Range: 400 8000
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("ATT_FILTER_RATE", 9, ParametersG2, att_filter_rate_hz, 1000),
AP_GROUPINFO("ATT_FILTER_RATE", 9, ParametersG2, att_filter_rate_hz, 0),

// @Param: ATT_LOG_RATE
// @DisplayName: Rate thread fast logging rate
// @Description: The rate of rate thread fast logging in Hz. The actual rate is constrained to be a whole divisor of the gyro rate and thus cannot be larger than the gyro rate.
// @Description: The rate of rate thread fast logging in Hz. The actual rate is constrained to be a whole divisor of the gyro rate and thus cannot be larger than the gyro rate. A value of 0 will utilize a rate equivalent to the main loop rate.
// @Range: 400 8000
// @Increment: 1
// @User: Advanced
Expand Down

0 comments on commit 1e7d0af

Please sign in to comment.