mirror of https://github.com/ArduPilot/ardupilot
Copter: rename FRAME to FRAME_TYPE
This unifies the plane and copter parameter names
This commit is contained in:
parent
934ef55338
commit
12d024e0c6
|
@ -490,7 +490,7 @@ void Copter::one_hz_loop()
|
|||
update_using_interlock();
|
||||
|
||||
// check the user hasn't updated the frame class or type
|
||||
motors.set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_orientation.get());
|
||||
motors.set_frame_class_and_type((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
||||
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
// set all throttle channel settings
|
||||
|
|
|
@ -385,12 +385,12 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @Range: 0 32767
|
||||
GSCALAR(radio_tuning_high, "TUNE_HIGH", 1000),
|
||||
|
||||
// @Param: FRAME
|
||||
// @DisplayName: Frame Orientation (+, X or V)
|
||||
// @Param: FRAME_TYPE
|
||||
// @DisplayName: Frame Type (+, X, V, etc)
|
||||
// @Description: Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
|
||||
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B (New)
|
||||
// @User: Standard
|
||||
GSCALAR(frame_orientation, "FRAME", AP_Motors::MOTOR_FRAME_TYPE_X),
|
||||
GSCALAR(frame_type, "FRAME_TYPE", AP_Motors::MOTOR_FRAME_TYPE_X),
|
||||
|
||||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
|
@ -1175,7 +1175,7 @@ void Copter::convert_pid_parameters(void)
|
|||
|
||||
#if FRAME_CONFIG == QUAD_FRAME || FRAME_CONFIG == HEXA_FRAME || FRAME_CONFIG == Y6_FRAME || FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
|
||||
// Multicopter x-frame gains are 40% lower because -1 or +1 input to motors now results in maximum rotation
|
||||
if (g.frame_orientation == AP_Motors::MOTOR_FRAME_TYPE_X || g.frame_orientation == AP_Motors::MOTOR_FRAME_TYPE_V || g.frame_orientation == AP_Motors::MOTOR_FRAME_TYPE_H) {
|
||||
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;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -236,7 +236,7 @@ public:
|
|||
k_param_compass_enabled,
|
||||
k_param_compass,
|
||||
k_param_rangefinder_enabled_old, // deprecated
|
||||
k_param_frame_orientation,
|
||||
k_param_frame_type,
|
||||
k_param_optflow_enabled, // deprecated
|
||||
k_param_fs_batt_voltage,
|
||||
k_param_ch7_option,
|
||||
|
@ -441,7 +441,7 @@ public:
|
|||
AP_Int8 radio_tuning;
|
||||
AP_Int16 radio_tuning_high;
|
||||
AP_Int16 radio_tuning_low;
|
||||
AP_Int8 frame_orientation;
|
||||
AP_Int8 frame_type;
|
||||
AP_Int8 ch7_option;
|
||||
AP_Int8 ch8_option;
|
||||
AP_Int8 ch9_option;
|
||||
|
|
|
@ -57,7 +57,7 @@ void Copter::init_rc_out()
|
|||
|
||||
motors.set_update_rate(g.rc_speed);
|
||||
motors.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||
motors.init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_orientation.get());
|
||||
motors.init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue