/* control of servo output ranges, trim and servo reversal. This can optionally be used to provide separation of input and output channel ranges so that RCn_MIN, RCn_MAX, RCn_TRIM and RCn_REV only apply to the input side of RC_Channel It works by running servo output calculations as normal, then re-mapping the output according to the servo MIN/MAX/TRIM/REV from this object Only 4 channels of ranges are defined as those match the input channels for R/C sticks */ #pragma once #include #include #include #include #include #include #include #include #include #ifndef NUM_SERVO_CHANNELS #if defined(HAL_BUILD_AP_PERIPH) && defined(HAL_PWM_COUNT) #define NUM_SERVO_CHANNELS HAL_PWM_COUNT #elif defined(HAL_BUILD_AP_PERIPH) #define NUM_SERVO_CHANNELS 0 #else #define NUM_SERVO_CHANNELS 16 #endif #endif class SRV_Channels; /* class SRV_Channel. The class SRV_Channels contains an array of SRV_Channel objects. This is done to fit within the AP_Param limit of 64 parameters per object. */ class SRV_Channel { public: friend class SRV_Channels; // constructor SRV_Channel(void); static const struct AP_Param::GroupInfo var_info[]; typedef enum { k_GPIO = -1, ///< used as GPIO pin (input or output) k_none = 0, ///< disabled k_manual = 1, ///< manual, just pass-thru the RC in signal k_flap = 2, ///< flap k_flap_auto = 3, ///< flap automated k_aileron = 4, ///< aileron k_unused1 = 5, ///< unused function k_mount_pan = 6, ///< mount yaw (pan) k_mount_tilt = 7, ///< mount pitch (tilt) k_mount_roll = 8, ///< mount roll k_mount_open = 9, ///< mount open (deploy) / close (retract) k_cam_trigger = 10, ///< camera trigger k_egg_drop = 11, ///< egg drop, deprecated k_mount2_pan = 12, ///< mount2 yaw (pan) k_mount2_tilt = 13, ///< mount2 pitch (tilt) k_mount2_roll = 14, ///< mount2 roll k_mount2_open = 15, ///< mount2 open (deploy) / close (retract) k_dspoilerLeft1 = 16, ///< differential spoiler 1 (left wing) k_dspoilerRight1 = 17, ///< differential spoiler 1 (right wing) k_aileron_with_input = 18, ///< aileron, with rc input, deprecated k_elevator = 19, ///< elevator k_elevator_with_input = 20, ///< elevator, with rc input, deprecated k_rudder = 21, ///< secondary rudder channel k_sprayer_pump = 22, ///< crop sprayer pump channel k_sprayer_spinner = 23, ///< crop sprayer spinner channel k_flaperon_left = 24, ///< flaperon, left wing k_flaperon_right = 25, ///< flaperon, right wing k_steering = 26, ///< ground steering, used to separate from rudder k_parachute_release = 27, ///< parachute release k_gripper = 28, ///< gripper k_landing_gear_control = 29, ///< landing gear controller k_engine_run_enable = 30, ///< engine kill switch, used for gas airplanes and helicopters k_heli_rsc = 31, ///< helicopter RSC output k_heli_tail_rsc = 32, ///< helicopter tail RSC output k_motor1 = 33, ///< these allow remapping of copter motors k_motor2 = 34, k_motor3 = 35, k_motor4 = 36, k_motor5 = 37, k_motor6 = 38, k_motor7 = 39, k_motor8 = 40, k_motor_tilt = 41, ///< tiltrotor motor tilt control k_generator_control = 42, ///< state control for generator k_tiltMotorRear = 45, ///dshot_esc_type.get()); } static SRV_Channel *srv_channel(uint8_t i) { #if NUM_SERVO_CHANNELS > 0 return i function_mask; static bool initialised; // this static arrangement is to avoid having static objects in AP_Param tables static SRV_Channel *channels; static SRV_Channels *_singleton; #ifndef HAL_BUILD_AP_PERIPH // support for Volz protocol AP_Volz_Protocol volz; static AP_Volz_Protocol *volz_ptr; // support for SBUS protocol AP_SBusOut sbus; static AP_SBusOut *sbus_ptr; // support for Robotis servo protocol AP_RobotisServo robotis; static AP_RobotisServo *robotis_ptr; #endif // HAL_BUILD_AP_PERIPH #if HAL_SUPPORT_RCOUT_SERIAL // support for BLHeli protocol AP_BLHeli blheli; static AP_BLHeli *blheli_ptr; #endif #if AP_FETTEC_ONEWIRE_ENABLED AP_FETtecOneWire fetteconwire; static AP_FETtecOneWire *fetteconwire_ptr; #endif // AP_FETTEC_ONEWIRE_ENABLED static uint16_t disabled_mask; // mask of outputs which use a digital output protocol, not // PWM (eg. DShot) static uint16_t digital_mask; // mask of outputs which are digitally reversible (eg. DShot-3D) static uint16_t reversible_mask; SRV_Channel obj_channels[NUM_SERVO_CHANNELS]; // override loop counter static uint16_t override_counter[NUM_SERVO_CHANNELS]; static struct srv_function { // mask of what channels this applies to SRV_Channel::servo_mask_t channel_mask; // scaled output for this function float output_scaled; } functions[SRV_Channel::k_nr_aux_servo_functions]; AP_Int8 auto_trim; AP_Int16 default_rate; AP_Int8 dshot_rate; AP_Int8 dshot_esc_type; AP_Int32 gpio_mask; // return true if passthrough is disabled static bool passthrough_disabled(void) { return disabled_passthrough; } static bool emergency_stop; // semaphore for multi-thread use of override_counter array HAL_Semaphore override_counter_sem; };