mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: fixed parameter handling for pointer objects
fixed loading of default files and use of POINTER flag on object groups
This commit is contained in:
parent
3338b4295e
commit
e85df47b06
@ -3,19 +3,6 @@
|
||||
// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
|
||||
// valid! You should switch to using a HAL_BOARD flag in your local config.mk.
|
||||
|
||||
//#define FRAME_CONFIG QUAD_FRAME
|
||||
/* options:
|
||||
* QUAD_FRAME
|
||||
* TRI_FRAME
|
||||
* HEXA_FRAME
|
||||
* Y6_FRAME
|
||||
* OCTA_FRAME
|
||||
* OCTA_QUAD_FRAME
|
||||
* HELI_FRAME
|
||||
* SINGLE_FRAME
|
||||
* COAX_FRAME
|
||||
*/
|
||||
|
||||
// uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards)
|
||||
//#define LOGGING_ENABLED DISABLED // disable dataflash logging to save 11K of flash space
|
||||
//#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space
|
||||
|
@ -24,6 +24,7 @@
|
||||
#define ASCALAR(v, name, def) { copter.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&copter.aparm.v, {def_value : def} }
|
||||
#define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &copter.g.v, {group_info : class::var_info} }
|
||||
#define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info} }
|
||||
#define GOBJECTPTR(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info}, AP_PARAM_FLAG_POINTER }
|
||||
#define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&copter.v, {group_info : class::var_info} }
|
||||
|
||||
const AP_Param::Info Copter::var_info[] = {
|
||||
@ -683,23 +684,19 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
|
||||
// @Group: WPNAV_
|
||||
// @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
|
||||
GOBJECT(wp_nav, "WPNAV_", AC_WPNav),
|
||||
GOBJECTPTR(wp_nav, "WPNAV_", AC_WPNav),
|
||||
|
||||
// @Group: CIRCLE_
|
||||
// @Path: ../libraries/AC_WPNav/AC_Circle.cpp
|
||||
GOBJECT(circle_nav, "CIRCLE_", AC_Circle),
|
||||
GOBJECTPTR(circle_nav, "CIRCLE_", AC_Circle),
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Heli),
|
||||
#else
|
||||
// @Group: ATC_
|
||||
// @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp
|
||||
GOBJECT(attitude_control, "ATC_", AC_AttitudeControl_Multi),
|
||||
#endif
|
||||
GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
|
||||
|
||||
// @Group: POSCON_
|
||||
// @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
|
||||
GOBJECT(pos_control, "PSC", AC_PosControl),
|
||||
GOBJECTPTR(pos_control, "PSC", AC_PosControl),
|
||||
|
||||
// @Group: SR0_
|
||||
// @Path: GCS_Mavlink.cpp
|
||||
@ -783,21 +780,11 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// @Group: H_
|
||||
// @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp
|
||||
GOBJECT(motors, "H_", AP_MotorsHeli_Single),
|
||||
|
||||
#elif FRAME_CONFIG == SINGLE_FRAME
|
||||
GOBJECT(motors, "MOT_", AP_MotorsSingle),
|
||||
|
||||
#elif FRAME_CONFIG == COAX_FRAME
|
||||
GOBJECT(motors, "MOT_", AP_MotorsCoax),
|
||||
|
||||
#elif FRAME_CONFIG == TRI_FRAME
|
||||
GOBJECT(motors, "MOT_", AP_MotorsTri),
|
||||
|
||||
GOBJECTPTR(motors, "H_", AP_MotorsHeli_Single),
|
||||
#else
|
||||
// @Group: MOT_
|
||||
// @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
|
||||
GOBJECT(motors, "MOT_", AP_MotorsMulticopter),
|
||||
GOBJECTPTR(motors, "MOT_", AP_MotorsMulticopter),
|
||||
#endif
|
||||
|
||||
// @Group: RCMAP_
|
||||
@ -1080,7 +1067,7 @@ void Copter::load_parameters(void)
|
||||
|
||||
uint32_t before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
AP_Param::load_all(false);
|
||||
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
|
||||
cliSerial->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
|
||||
@ -1135,7 +1122,7 @@ void Copter::convert_pid_parameters(void)
|
||||
// and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500
|
||||
float pid_scaler = 1.27f;
|
||||
|
||||
#if FRAME_CONFIG == QUAD_FRAME || FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME || FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
// Multicopter x-frame gains are 40% lower because -1 or +1 input to motors now results in maximum rotation
|
||||
if (g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_X || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_V || g.frame_type == AP_Motors::MOTOR_FRAME_TYPE_H) {
|
||||
pid_scaler = 0.9f;
|
||||
|
@ -61,7 +61,7 @@
|
||||
// FRAME_CONFIG
|
||||
//
|
||||
#ifndef FRAME_CONFIG
|
||||
# define FRAME_CONFIG QUAD_FRAME
|
||||
# define FRAME_CONFIG MULTICOPTER_FRAME
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////
|
||||
@ -73,23 +73,6 @@
|
||||
# define AUTOTUNE_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////
|
||||
// Y6 defaults
|
||||
#if FRAME_CONFIG == Y6_FRAME
|
||||
# define RATE_ROLL_P 0.1f
|
||||
# define RATE_ROLL_D 0.006f
|
||||
# define RATE_PITCH_P 0.1f
|
||||
# define RATE_PITCH_D 0.006f
|
||||
# define RATE_YAW_P 0.150f
|
||||
# define RATE_YAW_I 0.015f
|
||||
#endif
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////
|
||||
// Tri defaults
|
||||
#if FRAME_CONFIG == TRI_FRAME
|
||||
# define RATE_YAW_FILT_HZ 100.0f
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// PWM control
|
||||
// default RC speed in Hz
|
||||
|
@ -75,15 +75,8 @@ enum aux_sw_func {
|
||||
|
||||
// Frame types
|
||||
#define UNDEFINED_FRAME 0
|
||||
#define QUAD_FRAME 1
|
||||
#define TRI_FRAME 2
|
||||
#define HEXA_FRAME 3
|
||||
#define Y6_FRAME 4
|
||||
#define OCTA_FRAME 5
|
||||
#define HELI_FRAME 6
|
||||
#define OCTA_QUAD_FRAME 7
|
||||
#define SINGLE_FRAME 8
|
||||
#define COAX_FRAME 9
|
||||
#define MULTICOPTER_FRAME 1
|
||||
#define HELI_FRAME 2
|
||||
|
||||
// HIL enumerations
|
||||
#define HIL_MODE_DISABLED 0
|
||||
|
@ -590,4 +590,24 @@ void Copter::allocate_motors(void)
|
||||
if (wp_nav == nullptr) {
|
||||
AP_HAL::panic("Unable to allocate CircleNav");
|
||||
}
|
||||
|
||||
// reload lines from the defaults file that may now be accessible
|
||||
AP_Param::reload_defaults_file();
|
||||
|
||||
// now setup some frame-class specific defaults
|
||||
switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) {
|
||||
case AP_Motors::MOTOR_FRAME_Y6:
|
||||
attitude_control->get_rate_roll_pid().kP().set_default(0.1);
|
||||
attitude_control->get_rate_roll_pid().kD().set_default(0.006);
|
||||
attitude_control->get_rate_pitch_pid().kP().set_default(0.1);
|
||||
attitude_control->get_rate_pitch_pid().kD().set_default(0.006);
|
||||
attitude_control->get_rate_yaw_pid().kP().set_default(0.15);
|
||||
attitude_control->get_rate_yaw_pid().kI().set_default(0.015);
|
||||
break;
|
||||
case AP_Motors::MOTOR_FRAME_TRI:
|
||||
attitude_control->get_rate_yaw_pid().filt_hz().set_default(100);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user