/* additional arming checks for plane */ #include "Plane.h" const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = { // variables from parent vehicle AP_NESTEDGROUPINFO(AP_Arming, 0), // @Param: RUDDER // @DisplayName: Rudder Arming // @Description: Control arm/disarm by rudder input. When enabled arming is done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero +- deadzone (RCx_DZ) // @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm // @User: Advanced AP_GROUPINFO("RUDDER", 3, AP_Arming_Plane, rudder_arming_value, ARMING_RUDDER_ARMONLY), AP_GROUPEND }; /* additional arming checks for plane */ bool AP_Arming_Plane::pre_arm_checks(bool report) { // call parent class checks bool ret = AP_Arming::pre_arm_checks(report); // Check airspeed sensor ret &= AP_Arming::airspeed_checks(report);
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- #include "RC_Channel_aux.h" #include <AP_Math.h> #include <AP_HAL.h> extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = { AP_NESTEDGROUPINFO(RC_Channel, 0), // @Param: FUNCTION // @DisplayName: Servo out function // @Description: Setting this to Disabled(0) will disable this output, any other value will enable the corresponding function // @Values: 0:Disabled,1:Manual,2:Flap,3:Flap_auto,4:Aileron,5:flaperon,6:mount_pan,7:mount_tilt,8:mount_roll,9:mount_open,10:camera_trigger,11:release,12:mount2_pan,13:mount2_tilt,14:mount2_roll,15:mount2_open,16:DifferentialSpoiler1,17:DifferentialSpoiler2,18:AileronWithInput // @User: Standard AP_GROUPINFO("FUNCTION", 1, RC_Channel_aux, function, 0), AP_GROUPEND }; static RC_Channel_aux *_aux_channels[7]; /// map a function to a servo channel and output it void RC_Channel_aux::output_ch(unsigned char ch_nr) { // take care of two corner cases switch(function) { case k_none: // disabled
*/ /* * AP_MotorsTri.cpp - ArduCopter motors library * Code by RandyMackay. DIYDrones.com * */ #include <AP_HAL/AP_HAL.h> #include <AP_Math/AP_Math.h> #include "AP_MotorsTri.h" extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_MotorsTri::var_info[] = { // variables from parent vehicle AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0), // parameters 1 ~ 29 were reserved for tradheli // parameters 30 ~ 39 reserved for tricopter // parameters 40 ~ 49 for single copter and coax copter (these have identical parameter files) // @Param: YAW_SV_REV // @DisplayName: Yaw Servo Reverse // @Description: Yaw servo reversing. Set to 1 for normal (forward) operation. Set to -1 to reverse this channel. // @Values: -1:Reversed,1:Normal // @User: Standard AP_GROUPINFO("YAW_SV_REV", 31, AP_MotorsTri, _yaw_servo_reverse, 1), // @Param: YAW_SV_TRIM // @DisplayName: Yaw Servo Trim/Center // @Description: Trim or center position of yaw servo
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- #include "AC_AttitudeControl_Heli.h" #include <AP_HAL/AP_HAL.h> // table of user settable parameters const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = { // parameters from parent vehicle AP_NESTEDGROUPINFO(AC_AttitudeControl, 0), AP_GROUPEND }; // passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf) { // store roll, pitch and passthroughs _passthrough_roll = roll_passthrough; _passthrough_pitch = pitch_passthrough; _passthrough_yaw = yaw_rate_bf; // set rate controller to use pass through _flags_heli.flybar_passthrough = true; // set bf rate targets to current body frame rates (i.e. relax and be ready for vehicle to switch out of acro) _rate_bf_desired.x = _ahrs.get_gyro().x * AC_ATTITUDE_CONTROL_DEGX100; _rate_bf_desired.y = _ahrs.get_gyro().y * AC_ATTITUDE_CONTROL_DEGX100; // accel limit desired yaw rate if (_accel_yaw_max > 0.0f) { float rate_change_limit = _accel_yaw_max * _dt;
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * GNU General Public License for more details. * * You should have received a copy of the GNU General Public License * along with this program. If not, see <http://www.gnu.org/licenses/>. */ #include <stdlib.h> #include <AP_HAL/AP_HAL.h> #include "AP_MotorsHeli_Dual.h" extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = { AP_NESTEDGROUPINFO(AP_MotorsHeli, 0), // @Param: SV1_POS // @DisplayName: Servo 1 Position // @Description: Angular location of swash servo #1 // @Range: -180 180 // @Units: deg // @User: Standard // @Increment: 1 AP_GROUPINFO("SV1_POS", 1, AP_MotorsHeli_Dual, _servo1_pos, AP_MOTORS_HELI_DUAL_SERVO1_POS), // @Param: SV2_POS // @DisplayName: Servo 2 Position // @Description: Angular location of swash servo #2 // @Range: -180 180 // @Units: deg
#include "Plane.h" /* the vehicle class has its own var table for TUNE_PARAM so it can have separate parameter docs for the list of available parameters */ const AP_Param::GroupInfo AP_Tuning_Plane::var_info[] = { // @Param: PARAM // @DisplayName: Transmitter tuning parameter or set of parameters // @Description: This sets which parameter or set of parameters will be tuned. Values greater than 100 indicate a set of parameters rather than a single parameter. Parameters less than 50 are for QuadPlane vertical lift motors only. // @Values: 0:None,1:RateRollPI,2:RateRollP,3:RateRollI,4:RateRollD,5:RatePitchPI,6:RatePitchP,7:RatePitchI,8:RatePitchD,9:RateYawPI,10:RateYawP,11:RateYawI,12:RateYawD,13:AngleRollP,14:AnglePitchP,15:AngleYawP,16:PosXYP,17:PosZP,18:VelXYP,19:VelXYI,20:VelZP,21:AccelZP,22:AccelZI,23:AccelZD,50:FixedWingRollP,51:FixedWingRollI,52:FixedWingRollD,53:FixedWingRollFF,54:FixedWingPitchP,55:FixedWingPitchI,56:FixedWingPitchD,57:FixedWingPitchFF,101:Set_RateRollPitch,102:Set_RateRoll,103:Set_RatePitch,104:Set_RateYaw,105:Set_AngleRollPitch,106:Set_VelXY,107:Set_AccelZ // @User: Standard AP_GROUPINFO("PARAM", 1, AP_Tuning_Plane, parmset, 0), // the rest of the parameters are from AP_Tuning AP_NESTEDGROUPINFO(AP_Tuning, 0), AP_GROUPEND }; /* tables of tuning sets */ const uint8_t AP_Tuning_Plane::tuning_set_rate_roll_pitch[] = { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_PI, TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI}; const uint8_t AP_Tuning_Plane::tuning_set_rate_roll[] = { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_PI }; const uint8_t AP_Tuning_Plane::tuning_set_rate_pitch[] = { TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI }; const uint8_t AP_Tuning_Plane::tuning_set_rate_yaw[] = { TUNING_RATE_YAW_P, TUNING_RATE_YAW_I, TUNING_RATE_YAW_D }; const uint8_t AP_Tuning_Plane::tuning_set_ang_roll_pitch[] = { TUNING_ANG_ROLL_P, TUNING_ANG_PITCH_P }; const uint8_t AP_Tuning_Plane::tuning_set_vxy[] = { TUNING_VXY_P, TUNING_VXY_I };
#include "AC_InputManager_Heli.h" #include <AP_Math/AP_Math.h> #include <AP_HAL/AP_HAL.h> extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AC_InputManager_Heli::var_info[] = { // parameters from parent vehicle AP_NESTEDGROUPINFO(AC_InputManager, 0), // @Param: STAB_COL_1 // @DisplayName: Stabilize Mode Collective Point 1 // @Description: Helicopter's minimum collective pitch setting at zero throttle input in Stabilize mode // @Range: 0 500 // @Units: Percent*10 // @Increment: 1 // @User: Standard AP_GROUPINFO("STAB_COL_1", 1, AC_InputManager_Heli, _heli_stab_col_min, AC_ATTITUDE_HELI_STAB_COLLECTIVE_MIN_DEFAULT), // @Param: STAB_COL_2 // @DisplayName: Stabilize Mode Collective Point 2 // @Description: Helicopter's collective pitch setting at mid-low throttle input in Stabilize mode // @Range: 0 500 // @Units: Percent*10 // @Increment: 1 // @User: Standard AP_GROUPINFO("STAB_COL_2", 2, AC_InputManager_Heli, _heli_stab_col_low, AC_ATTITUDE_HELI_STAB_COLLECTIVE_LOW_DEFAULT), // @Param: STAB_COL_3 // @DisplayName: Stabilize Mode Collective Point 3