mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_OpticalFlow: correct compilation when HAL_LOGGING_ENABLED is 0
This commit is contained in:
parent
7a33c753cb
commit
f14aab29e5
@ -270,9 +270,12 @@ void AP_OpticalFlow::update_state(const OpticalFlow_state &state)
|
|||||||
_last_update_ms,
|
_last_update_ms,
|
||||||
get_pos_offset(),
|
get_pos_offset(),
|
||||||
get_height_override());
|
get_height_override());
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
Log_Write_Optflow();
|
Log_Write_Optflow();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_OpticalFlow::Log_Write_Optflow()
|
void AP_OpticalFlow::Log_Write_Optflow()
|
||||||
{
|
{
|
||||||
AP_Logger *logger = AP_Logger::get_singleton();
|
AP_Logger *logger = AP_Logger::get_singleton();
|
||||||
@ -295,7 +298,7 @@ void AP_OpticalFlow::Log_Write_Optflow()
|
|||||||
};
|
};
|
||||||
logger->WriteBlock(&pkt, sizeof(pkt));
|
logger->WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
#endif // HAL_LOGGING_ENABLED
|
||||||
|
|
||||||
|
|
||||||
// singleton instance
|
// singleton instance
|
||||||
|
@ -141,7 +141,9 @@ void AP_OpticalFlow_Calibrator::add_sample(uint32_t timestamp_ms, const Vector2f
|
|||||||
// check enough roll or pitch movement and record sample
|
// check enough roll or pitch movement and record sample
|
||||||
const bool rates_x_sufficient = (fabsf(body_rate.x) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS) && (fabsf(flow_rate.x) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS);
|
const bool rates_x_sufficient = (fabsf(body_rate.x) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS) && (fabsf(flow_rate.x) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS);
|
||||||
if (rates_x_sufficient && (_cal_data[0].num_samples < ARRAY_SIZE(_cal_data[0].samples))) {
|
if (rates_x_sufficient && (_cal_data[0].num_samples < ARRAY_SIZE(_cal_data[0].samples))) {
|
||||||
|
# if HAL_LOGGING_ENABLED
|
||||||
log_sample(0, _cal_data[0].num_samples, flow_rate.x, body_rate.x, los_pred.x);
|
log_sample(0, _cal_data[0].num_samples, flow_rate.x, body_rate.x, los_pred.x);
|
||||||
|
#endif
|
||||||
_cal_data[0].samples[_cal_data[0].num_samples].flow_rate = flow_rate.x;
|
_cal_data[0].samples[_cal_data[0].num_samples].flow_rate = flow_rate.x;
|
||||||
_cal_data[0].samples[_cal_data[0].num_samples].body_rate = body_rate.x;
|
_cal_data[0].samples[_cal_data[0].num_samples].body_rate = body_rate.x;
|
||||||
_cal_data[0].samples[_cal_data[0].num_samples].los_pred = los_pred.x;
|
_cal_data[0].samples[_cal_data[0].num_samples].los_pred = los_pred.x;
|
||||||
@ -149,7 +151,9 @@ void AP_OpticalFlow_Calibrator::add_sample(uint32_t timestamp_ms, const Vector2f
|
|||||||
}
|
}
|
||||||
const bool rates_y_sufficient = (fabsf(body_rate.y) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS) && (fabsf(flow_rate.y) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS);
|
const bool rates_y_sufficient = (fabsf(body_rate.y) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS) && (fabsf(flow_rate.y) >= AP_OPTICALFLOW_CAL_ROLLPITCH_MIN_RADS);
|
||||||
if (rates_y_sufficient && (_cal_data[1].num_samples < ARRAY_SIZE(_cal_data[1].samples))) {
|
if (rates_y_sufficient && (_cal_data[1].num_samples < ARRAY_SIZE(_cal_data[1].samples))) {
|
||||||
|
# if HAL_LOGGING_ENABLED
|
||||||
log_sample(1, _cal_data[1].num_samples, flow_rate.y, body_rate.y, los_pred.y);
|
log_sample(1, _cal_data[1].num_samples, flow_rate.y, body_rate.y, los_pred.y);
|
||||||
|
#endif
|
||||||
_cal_data[1].samples[_cal_data[1].num_samples].flow_rate = flow_rate.y;
|
_cal_data[1].samples[_cal_data[1].num_samples].flow_rate = flow_rate.y;
|
||||||
_cal_data[1].samples[_cal_data[1].num_samples].body_rate = body_rate.y;
|
_cal_data[1].samples[_cal_data[1].num_samples].body_rate = body_rate.y;
|
||||||
_cal_data[1].samples[_cal_data[1].num_samples].los_pred = los_pred.y;
|
_cal_data[1].samples[_cal_data[1].num_samples].los_pred = los_pred.y;
|
||||||
@ -298,6 +302,7 @@ float AP_OpticalFlow_Calibrator::calc_mean_squared_residuals(uint8_t axis, float
|
|||||||
return sum;
|
return sum;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log all samples
|
// log all samples
|
||||||
void AP_OpticalFlow_Calibrator::log_sample(uint8_t axis, uint8_t sample_num, float flow_rate, float body_rate, float los_pred)
|
void AP_OpticalFlow_Calibrator::log_sample(uint8_t axis, uint8_t sample_num, float flow_rate, float body_rate, float los_pred)
|
||||||
{
|
{
|
||||||
@ -323,3 +328,4 @@ void AP_OpticalFlow_Calibrator::log_sample(uint8_t axis, uint8_t sample_num, flo
|
|||||||
(double)body_rate,
|
(double)body_rate,
|
||||||
(double)los_pred);
|
(double)los_pred);
|
||||||
}
|
}
|
||||||
|
#endif // HAL_LOGGING_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user