APM:Libraries
Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
SRV_Channel Class Reference

#include <SRV_Channel.h>

Collaboration diagram for SRV_Channel:
[legend]

Public Types

enum  Aux_servo_function_t {
  k_none = 0, k_manual = 1, k_flap = 2, k_flap_auto = 3,
  k_aileron = 4, k_unused1 = 5, k_mount_pan = 6, k_mount_tilt = 7,
  k_mount_roll = 8, k_mount_open = 9, k_cam_trigger = 10, k_egg_drop = 11,
  k_mount2_pan = 12, k_mount2_tilt = 13, k_mount2_roll = 14, k_mount2_open = 15,
  k_dspoilerLeft1 = 16, k_dspoilerRight1 = 17, k_aileron_with_input = 18, k_elevator = 19,
  k_elevator_with_input = 20, k_rudder = 21, k_sprayer_pump = 22, k_sprayer_spinner = 23,
  k_flaperon_left = 24, k_flaperon_right = 25, k_steering = 26, k_parachute_release = 27,
  k_gripper = 28, k_landing_gear_control = 29, k_engine_run_enable = 30, k_heli_rsc = 31,
  k_heli_tail_rsc = 32, k_motor1 = 33, 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, k_rcin1 = 51, k_rcin2 = 52,
  k_rcin3 = 53, k_rcin4 = 54, k_rcin5 = 55, k_rcin6 = 56,
  k_rcin7 = 57, k_rcin8 = 58, k_rcin9 = 59, k_rcin10 = 60,
  k_rcin11 = 61, k_rcin12 = 62, k_rcin13 = 63, k_rcin14 = 64,
  k_rcin15 = 65, k_rcin16 = 66, k_ignition = 67, k_choke = 68,
  k_starter = 69, k_throttle = 70, k_tracker_yaw = 71, k_tracker_pitch = 72,
  k_throttleLeft = 73, k_throttleRight = 74, k_tiltMotorLeft = 75, k_tiltMotorRight = 76,
  k_elevon_left = 77, k_elevon_right = 78, k_vtail_left = 79, k_vtail_right = 80,
  k_boost_throttle = 81, k_motor9 = 82, k_motor10 = 83, k_motor11 = 84,
  k_motor12 = 85, k_dspoilerLeft2 = 86, k_dspoilerRight2 = 87, k_winch = 88,
  k_nr_aux_servo_functions
}
 
enum  LimitValue { SRV_CHANNEL_LIMIT_TRIM, SRV_CHANNEL_LIMIT_MIN, SRV_CHANNEL_LIMIT_MAX, SRV_CHANNEL_LIMIT_ZERO_PWM }
 

Public Member Functions

 SRV_Channel (void)
 
void set_output_pwm (uint16_t pwm)
 
uint16_t get_output_pwm (void) const
 
void set_angle (int16_t angle)
 
void set_range (uint16_t high)
 
bool get_reversed (void) const
 
void set_output_min (uint16_t pwm)
 
void set_output_max (uint16_t pwm)
 
uint16_t get_output_min (void) const
 
uint16_t get_output_max (void) const
 
uint16_t get_trim (void) const
 
SRV_Channel::Aux_servo_function_t get_function (void) const
 
void function_set_and_save (SRV_Channel::Aux_servo_function_t f)
 
void reversed_set_and_save_ifchanged (bool r)
 
bool function_configured (void) const
 

Static Public Member Functions

static bool is_motor (SRV_Channel::Aux_servo_function_t function)
 

Static Public Attributes

static const struct AP_Param::GroupInfo var_info []
 

Private Types

typedef uint16_t servo_mask_t
 

Private Member Functions

uint16_t pwm_from_range (int16_t scaled_value) const
 
uint16_t pwm_from_angle (int16_t scaled_value) const
 
void calc_pwm (int16_t output_scaled)
 
void output_ch (void)
 map a function to a servo channel and output it More...
 
void aux_servo_function_setup (void)
 
uint16_t get_limit_pwm (LimitValue limit) const
 
float get_output_norm (void)
 

Private Attributes

AP_Int16 servo_min
 
AP_Int16 servo_max
 
AP_Int16 servo_trim
 
AP_Int8 reversed
 
AP_Int8 function
 
uint16_t output_pwm
 
bool type_angle:1
 
bool type_setup:1
 
uint8_t ch_num
 
uint16_t high_out
 

Static Private Attributes

static servo_mask_t have_pwm_mask
 

Friends

class SRV_Channels
 

Detailed Description

Definition at line 33 of file SRV_Channel.h.

Member Typedef Documentation

◆ servo_mask_t

typedef uint16_t SRV_Channel::servo_mask_t
private

Definition at line 241 of file SRV_Channel.h.

Member Enumeration Documentation

◆ Aux_servo_function_t

Enumerator
k_none 

disabled

k_manual 

manual, just pass-thru the RC in signal

k_flap 

flap

k_flap_auto 

flap automated

k_aileron 

aileron

k_unused1 

unused function

k_mount_pan 

mount yaw (pan)

k_mount_tilt 

mount pitch (tilt)

k_mount_roll 

mount roll

k_mount_open 

mount open (deploy) / close (retract)

k_cam_trigger 

camera trigger

k_egg_drop 

egg drop

k_mount2_pan 

mount2 yaw (pan)

k_mount2_tilt 

mount2 pitch (tilt)

k_mount2_roll 

mount2 roll

k_mount2_open 

mount2 open (deploy) / close (retract)

k_dspoilerLeft1 

differential spoiler 1 (left wing)

k_dspoilerRight1 

differential spoiler 1 (right wing)

k_aileron_with_input 

aileron, with rc input, deprecated

k_elevator 

elevator

k_elevator_with_input 

elevator, with rc input, deprecated

k_rudder 

secondary rudder channel

k_sprayer_pump 

crop sprayer pump channel

k_sprayer_spinner 

crop sprayer spinner channel

k_flaperon_left 

flaperon, left wing

k_flaperon_right 

flaperon, right wing

k_steering 

ground steering, used to separate from rudder

k_parachute_release 

parachute release

k_gripper 

gripper

k_landing_gear_control 

landing gear controller

k_engine_run_enable 

engine kill switch, used for gas airplanes and helicopters

k_heli_rsc 

helicopter RSC output

k_heli_tail_rsc 

helicopter tail RSC output

k_motor1 

these allow remapping of copter motors

k_motor2 
k_motor3 
k_motor4 
k_motor5 
k_motor6 
k_motor7 
k_motor8 
k_motor_tilt 

tiltrotor motor tilt control

k_rcin1 

these are for pass-thru from arbitrary rc inputs

k_rcin2 
k_rcin3 
k_rcin4 
k_rcin5 
k_rcin6 
k_rcin7 
k_rcin8 
k_rcin9 
k_rcin10 
k_rcin11 
k_rcin12 
k_rcin13 
k_rcin14 
k_rcin15 
k_rcin16 
k_ignition 
k_choke 
k_starter 
k_throttle 
k_tracker_yaw 

antennatracker yaw

k_tracker_pitch 

antennatracker pitch

k_throttleLeft 
k_throttleRight 
k_tiltMotorLeft 

vectored thrust, left tilt

k_tiltMotorRight 

vectored thrust, right tilt

k_elevon_left 
k_elevon_right 
k_vtail_left 
k_vtail_right 
k_boost_throttle 

vertical booster throttle

k_motor9 
k_motor10 
k_motor11 
k_motor12 
k_dspoilerLeft2 

differential spoiler 2 (left wing)

k_dspoilerRight2 

differential spoiler 2 (right wing)

k_winch 
k_nr_aux_servo_functions 

This must be the last enum value (only add new values before this one)

Definition at line 42 of file SRV_Channel.h.

◆ LimitValue

Enumerator
SRV_CHANNEL_LIMIT_TRIM 
SRV_CHANNEL_LIMIT_MIN 
SRV_CHANNEL_LIMIT_MAX 
SRV_CHANNEL_LIMIT_ZERO_PWM 

Definition at line 128 of file SRV_Channel.h.

Constructor & Destructor Documentation

◆ SRV_Channel()

SRV_Channel::SRV_Channel ( void  )

Definition at line 76 of file SRV_Channel.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ aux_servo_function_setup()

void SRV_Channel::aux_servo_function_setup ( void  )
private

Definition at line 82 of file SRV_Channel_aux.cpp.

Here is the call graph for this function:

◆ calc_pwm()

void SRV_Channel::calc_pwm ( int16_t  output_scaled)
private

Definition at line 110 of file SRV_Channel.cpp.

Referenced by SRV_Channels::calc_pwm(), SRV_Channels::disable_passthrough(), and SRV_Channels::limit_slew_rate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ function_configured()

bool SRV_Channel::function_configured ( void  ) const
inline

Definition at line 192 of file SRV_Channel.h.

◆ function_set_and_save()

void SRV_Channel::function_set_and_save ( SRV_Channel::Aux_servo_function_t  f)
inline

Definition at line 180 of file SRV_Channel.h.

◆ get_function()

SRV_Channel::Aux_servo_function_t SRV_Channel::get_function ( void  ) const
inline

Definition at line 175 of file SRV_Channel.h.

Referenced by AP_Arming::servo_checks().

Here is the caller graph for this function:

◆ get_limit_pwm()

uint16_t SRV_Channel::get_limit_pwm ( LimitValue  limit) const
private

Definition at line 169 of file SRV_Channel.cpp.

Referenced by SRV_Channels::set_failsafe_limit(), SRV_Channels::set_output_limit(), and SRV_Channels::set_safety_limit().

Here is the caller graph for this function:

◆ get_output_max()

uint16_t SRV_Channel::get_output_max ( void  ) const
inline

◆ get_output_min()

uint16_t SRV_Channel::get_output_min ( void  ) const
inline

◆ get_output_norm()

float SRV_Channel::get_output_norm ( void  )
private

Definition at line 149 of file SRV_Channel.cpp.

Here is the call graph for this function:

◆ get_output_pwm()

uint16_t SRV_Channel::get_output_pwm ( void  ) const
inline

Definition at line 139 of file SRV_Channel.h.

Referenced by GCS_MAVLINK::send_servo_output_raw(), AP_SBusOut::update(), AP_Volz_Protocol::update(), and AP_Landing_Deepstall::verify_land().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_reversed()

bool SRV_Channel::get_reversed ( void  ) const
inline

Definition at line 148 of file SRV_Channel.h.

Referenced by AP_Motors::calc_pwm_output_0to1(), AP_Motors::calc_pwm_output_1to1(), AP_MotorsHeli::calc_pwm_output_1to1_swash_servo(), AP_MotorsTri::calc_yaw_radio_output(), get_output_norm(), SRV_Channels::move_servo(), and SRV_Channels::set_trim_to_min_for().

Here is the caller graph for this function:

◆ get_trim()

uint16_t SRV_Channel::get_trim ( void  ) const
inline

Definition at line 167 of file SRV_Channel.h.

Referenced by AP_Motors::calc_pwm_output_1to1(), AP_MotorsHeli::calc_pwm_output_1to1_swash_servo(), AP_MotorsTri::calc_yaw_radio_output(), AP_MotorsTri::output_motor_mask(), AP_MotorsTri::output_to_motors(), AP_Arming::servo_checks(), and AP_ServoRelayEvents::update_events().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_motor()

bool SRV_Channel::is_motor ( SRV_Channel::Aux_servo_function_t  function)
static

Definition at line 185 of file SRV_Channel.cpp.

Referenced by get_trim().

Here is the caller graph for this function:

◆ output_ch()

void SRV_Channel::output_ch ( void  )
private

map a function to a servo channel and output it

Definition at line 28 of file SRV_Channel_aux.cpp.

Here is the call graph for this function:

◆ pwm_from_angle()

uint16_t SRV_Channel::pwm_from_angle ( int16_t  scaled_value) const
private

Definition at line 97 of file SRV_Channel.cpp.

Referenced by calc_pwm().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pwm_from_range()

uint16_t SRV_Channel::pwm_from_range ( int16_t  scaled_value) const
private

Definition at line 84 of file SRV_Channel.cpp.

Referenced by calc_pwm().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reversed_set_and_save_ifchanged()

void SRV_Channel::reversed_set_and_save_ifchanged ( bool  r)
inline

Definition at line 185 of file SRV_Channel.h.

◆ set_angle()

void SRV_Channel::set_angle ( int16_t  angle)

Definition at line 131 of file SRV_Channel.cpp.

Referenced by aux_servo_function_setup(), get_output_pwm(), AP_MotorsHeli_Single::init_outputs(), SRV_Channels::set_reversible_throttle(), and setup().

Here is the caller graph for this function:

◆ set_output_max()

void SRV_Channel::set_output_max ( uint16_t  pwm)
inline

Definition at line 156 of file SRV_Channel.h.

Referenced by AP_MotorsHeli::reset_swash_servo(), and setup().

Here is the caller graph for this function:

◆ set_output_min()

void SRV_Channel::set_output_min ( uint16_t  pwm)
inline

Definition at line 153 of file SRV_Channel.h.

Referenced by AP_MotorsHeli::reset_swash_servo(), and setup().

Here is the caller graph for this function:

◆ set_output_pwm()

void SRV_Channel::set_output_pwm ( uint16_t  pwm)

Definition at line 124 of file SRV_Channel.cpp.

Referenced by calc_pwm(), AP_ServoRelayEvents::do_set_servo(), SRV_Channels::move_servo(), SRV_Channels::output_trim_all(), AP_Landing_Deepstall::override_servos(), SRV_Channels::set_output_limit(), SRV_Channels::set_output_pwm_chan(), and AP_ServoRelayEvents::update_events().

Here is the caller graph for this function:

◆ set_range()

void SRV_Channel::set_range ( uint16_t  high)

Definition at line 139 of file SRV_Channel.cpp.

Referenced by aux_servo_function_setup(), get_output_pwm(), AP_MotorsHeli::reset_swash_servo(), SRV_Channels::set_reversible_throttle(), and setup().

Here is the caller graph for this function:

Friends And Related Function Documentation

◆ SRV_Channels

friend class SRV_Channels
friend

Definition at line 35 of file SRV_Channel.h.

Member Data Documentation

◆ ch_num

uint8_t SRV_Channel::ch_num
private

◆ function

AP_Int8 SRV_Channel::function
private

◆ have_pwm_mask

SRV_Channel::servo_mask_t SRV_Channel::have_pwm_mask
staticprivate

◆ high_out

uint16_t SRV_Channel::high_out
private

Definition at line 217 of file SRV_Channel.h.

Referenced by pwm_from_angle(), pwm_from_range(), set_angle(), and set_range().

◆ output_pwm

uint16_t SRV_Channel::output_pwm
private

◆ reversed

AP_Int8 SRV_Channel::reversed
private

◆ servo_max

AP_Int16 SRV_Channel::servo_max
private

◆ servo_min

AP_Int16 SRV_Channel::servo_min
private

◆ servo_trim

AP_Int16 SRV_Channel::servo_trim
private

◆ type_angle

bool SRV_Channel::type_angle
private

Definition at line 208 of file SRV_Channel.h.

Referenced by calc_pwm(), set_angle(), and set_range().

◆ type_setup

bool SRV_Channel::type_setup
private

Definition at line 211 of file SRV_Channel.h.

Referenced by aux_servo_function_setup(), set_angle(), and set_range().

◆ var_info

const AP_Param::GroupInfo SRV_Channel::var_info
static

Definition at line 40 of file SRV_Channel.h.

Referenced by SRV_Channel().


The documentation for this class was generated from the following files: