Browse Source

AP_BoardConfig: moved board dependent pieces from .h to .cpp

improves ccache efficiency
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
3e1ffa3769
  1. 12
      libraries/AP_BoardConfig/AP_BoardConfig.cpp
  2. 13
      libraries/AP_BoardConfig/AP_BoardConfig.h

12
libraries/AP_BoardConfig/AP_BoardConfig.cpp

@ -77,6 +77,18 @@ @@ -77,6 +77,18 @@
extern const AP_HAL::HAL& hal;
AP_BoardConfig *AP_BoardConfig::_singleton;
// constructor
AP_BoardConfig::AP_BoardConfig()
#if HAL_HAVE_IMU_HEATER
// initialise heater PI controller. Note we do this in the cpp file
// for ccache efficiency
: heater{{HAL_IMUHEAT_P_DEFAULT, HAL_IMUHEAT_I_DEFAULT, 70},}
#endif
{
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
};
// table of user settable parameters
const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {

13
libraries/AP_BoardConfig/AP_BoardConfig.h

@ -44,10 +44,7 @@ extern "C" typedef int (*main_fn_t)(int argc, char **); @@ -44,10 +44,7 @@ extern "C" typedef int (*main_fn_t)(int argc, char **);
class AP_BoardConfig {
public:
AP_BoardConfig() {
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
};
AP_BoardConfig();
/* Do not allow copies */
AP_BoardConfig(const AP_BoardConfig &other) = delete;
@ -124,12 +121,10 @@ public: @@ -124,12 +121,10 @@ public:
#endif
}
#ifdef HAL_PIN_ALT_CONFIG
// get alternative config selection
uint8_t get_alt_config(void) {
return uint8_t(_alt_config.get());
}
#endif // HAL_PIN_ALT_CONFIG
enum board_safety_button_option {
BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF= (1 << 0),
@ -254,9 +249,9 @@ private: @@ -254,9 +249,9 @@ private:
#if HAL_HAVE_IMU_HEATER
struct {
AC_PI pi_controller;
AP_Int8 imu_target_temperature;
uint32_t last_update_ms;
AC_PI pi_controller{HAL_IMUHEAT_P_DEFAULT, HAL_IMUHEAT_I_DEFAULT, 70};
uint16_t count;
float sum;
float output;
@ -282,9 +277,7 @@ private: @@ -282,9 +277,7 @@ private:
AP_Float _vservo_min;
#endif
#ifdef HAL_GPIO_PWM_VOLT_PIN
AP_Int8 _pwm_volt_sel;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
AP_Int8 _sdcard_slowdown;
@ -294,9 +287,7 @@ private: @@ -294,9 +287,7 @@ private:
AP_Int32 _options;
#ifdef HAL_PIN_ALT_CONFIG
AP_Int8 _alt_config;
#endif
};
namespace AP {

Loading…
Cancel
Save