iNavFlight / inav

INAV: Navigation-enabled flight control software
https://inavflight.github.io
GNU General Public License v3.0
3.14k stars 1.48k forks source link

Channel forwarding not functional on SPRacingF3 EVO board #600

Closed csarka closed 7 years ago

csarka commented 8 years ago

I just updated my multirotor from inav 1.1 to 1.2. I am using the RMDO flight controller. I'm having trouble now controlling any servo via AUX channel.

Previously (inav 1.1), the servo worked (AUX 3) with FEATURE SERVO_TILT enabled. Strangely CHANNEL_FORWARDING did not need to be enabled.

Now (inav 1.2), no combination of SERVO_TILT enabled/disabled and/or CHANNEL_FORWARDING enabled/disabled will allow any servo action on any AUX channel.

Are servos on AUX channel still working?

Dumps before and after are attached. dump_9-10-16_inav1.1.txt dump_9-12-16_inav1.2.txt

Thanks for your help,

Teja28 commented 8 years ago

Same problem...

xdigyx commented 8 years ago

Not missing, just reconfigured. Read last posts on #539

csarka commented 8 years ago

I tried enabling CAMSTAB: aux 6 7 2 900 2100 with various combinations of SERVO_TILT and CHANNEL_FORWARDING still no success... The first 4 channels are for the motors, that means any of the last 4 should be available for servo, right ? @Teja28 Can you able to enable CAMSTAB mode and try as @xdigyx susggests in #539 ?

xdigyx commented 8 years ago

no.. you did not read the issue I posted carefully... FEATURE_CHANNEL_FORWARDING - all motors are available, AUX are forwarded to RC5-8. FEATURE_SERVO_TILT - servos are enabled on M1-2, M3-6 are used for motors FEATURE_SERVO_TILT only is driving servos if CAMSTAB mode is enabled. FEATURE_CHANNEL_FORWARDING + FEATURE_SERVO_TILT - servos are enabled on M1-2, AUX are forwarded to RC5-8

@digitalentity Probably this should be included/better located in the docs to avoid the questions again.

JPRivet commented 8 years ago

Could you elaborate on what RC5-8 is referring to please? Does this mean the outputs are available on M5-8 on a F3 FC?

Thanks

DzikuVx commented 8 years ago

@JPRivet RC5-8 stands for RC input pins 5 to 8. Some inputs can be remapped to outputs

JPRivet commented 8 years ago

Ah ok - thanks!

On a SPRacingF3 EVO, it doesn't have these pins (RC1-8) since it's designed for PPM/SBUS instead - is this correct?

csarka commented 8 years ago

Thank you @DzikuVx DzikuVx That explains a lot! I am trying to enable at least one servo output on M5-8. (M1-4 are connected to the ESCs). RC-5-8 are already occupied for other I/O. Using the RMRC Dodo Rev 3a. I have tried using M6, M7, and M8 with every combination of features, still no success.

DzikuVx commented 8 years ago

@csarka unfortunately we are quite limited here and without complete rework of code that drives output mappings there is not much we can do.

krzysztofmatula commented 8 years ago

So, does it mean that CHANNEL_FORWARDING is not supposed to work for SPF3-EVO? INAV-1.2 includes this fix: https://github.com/iNavFlight/inav/pull/481. I wonder what it actually does...?

krzysztofmatula commented 8 years ago

I'm trying to use the CHANNEL_FORWARDING on SPF3-EVO without success... I have 4 motors on outputs 1-4 which provide PWM at ~400Hz. Outputs 5-8 are constantly silent (no PWM). Can someone confirm if the channel forwarding should be working on this board or not? I'm observing the issue on INAV-1.2.1 as well as on INAV-1.3-rc1.

Here's my bootlog:

Time Evt Description Parameters 0: 0 CONFIG_LOADED 0: 1 SYSTEM_INIT_DONE 501: 19 TIMER_CHANNEL_MAPPED (0, 0, 0, 0) 501: 19 TIMER_CHANNEL_MAPPED (1, 1, 0, 2) 501: 19 TIMER_CHANNEL_MAPPED (2, 2, 0, 2) 501: 19 TIMER_CHANNEL_MAPPED (3, 3, 0, 2) 501: 19 TIMER_CHANNEL_MAPPED (4, 4, 0, 2) 501: 19 TIMER_CHANNEL_MAPPED (5, 5, 0, 2) 501: 19 TIMER_CHANNEL_MAPPED (6, 6, 0, 2) 501: 19 TIMER_CHANNEL_MAPPED (7, 7, 0, 2) 501: 19 TIMER_CHANNEL_MAPPED (8, 8, 0, 2) 501: 18 TIMER_CHANNEL_SKIPPED (9, 8, 0, 3) 501: 18 TIMER_CHANNEL_SKIPPED (10, 8, 0, 3) 501: 2 PWM_INIT_DONE 511: 3 EXTRA_BOOT_DELAY 1056: 9 GYRO_DETECTION (7, 0, 0, 0) 1517: 10 ACC_DETECTION (8, 0, 0, 0) 1556: 11 BARO_DETECTION (4, 0, 0, 0) 1605: 12 MAG_DETECTION (6, 0, 0, 0) 1685: 4 SENSOR_INIT_DONE 2387: 5 GPS_INIT_DONE 2387: 6 LEDSTRIP_INIT_DONE 2387: 7 TELEMETRY_INIT_DONE 3398: 8 SYSTEM_READY

digitalentity commented 8 years ago

Please provide the dump and confirm that you are trying the latest firmware

krzysztofmatula commented 8 years ago

Here's the dump (latest firmware):

# dump

# version
# INAV/SPRACINGF3EVO 1.3.0 Oct 15 2016 / 08:42:45 (d54a6c5)
# pflags
# Persistent config flags: 0x00000000
# dump master

# mixer
mixer QUADX
mmix reset
smix reset

# feature
feature -RX_PPM
feature -VBAT
feature -UNUSED_1
feature -RX_SERIAL
feature -MOTOR_STOP
feature -SERVO_TILT
feature -SOFTSERIAL
feature -GPS
feature -FAILSAFE
feature -SONAR
feature -TELEMETRY
feature -CURRENT_METER
feature -3D
feature -RX_PARALLEL_PWM
feature -RX_MSP
feature -RSSI_ADC
feature -LED_STRIP
feature -DISPLAY
feature -UNUSED_2
feature -BLACKBOX
feature -CHANNEL_FORWARDING
feature -TRANSPONDER
feature -AIRMODE
feature -SUPEREXPO
feature -VTX
feature -RX_SPI
feature -SOFTSPI
feature -PWM_SERVO_DRIVER
feature RX_PPM
feature VBAT
feature GPS
feature FAILSAFE
feature TELEMETRY
feature RSSI_ADC
feature LED_STRIP
feature BLACKBOX
feature CHANNEL_FORWARDING

# beeper
beeper GYRO_CALIBRATED
beeper RX_LOST
beeper RX_LOST_LANDING
beeper DISARMING
beeper ARMING
beeper ARMING_GPS_FIX
beeper BAT_CRIT_LOW
beeper BAT_LOW
beeper GPS_STATUS
beeper RX_SET
beeper ACC_CALIBRATION
beeper ACC_CALIBRATION_FAIL
beeper READY_BEEP
beeper MULTI_BEEPS
beeper DISARM_REPEAT
beeper ARMED
beeper SYSTEM_INIT
beeper -ON_USB

# map
map AETR1234

# serial
serial 20 1 115200 38400 0 115200
serial 0 1 115200 38400 0 115200
serial 1 16 115200 38400 57600 115200
serial 2 2 115200 57600 0 115200

# led
led 0 7,0::CW:1
led 1 0,0::C:0
led 2 0,0::C:0
led 3 0,0::C:0
led 4 0,0::C:0
led 5 0,0::C:0
led 6 0,0::C:0
led 7 0,0::C:0
led 8 0,0::C:0
led 9 0,0::C:0
led 10 0,0::C:0
led 11 0,0::C:0
led 12 0,0::C:0
led 13 0,0::C:0
led 14 0,0::C:0
led 15 0,0::C:0
led 16 0,0::C:0
led 17 0,0::C:0
led 18 0,0::C:0
led 19 0,0::C:0
led 20 0,0::C:0
led 21 0,0::C:0
led 22 0,0::C:0
led 23 0,0::C:0
led 24 0,0::C:0
led 25 0,0::C:0
led 26 0,0::C:0
led 27 0,0::C:0
led 28 0,0::C:0
led 29 0,0::C:0
led 30 0,0::C:0
led 31 0,0::C:0

# color
color 0 0,0,0
color 1 0,255,255
color 2 0,0,255
color 3 30,0,255
color 4 60,0,255
color 5 90,0,255
color 6 120,0,255
color 7 150,0,255
color 8 180,0,255
color 9 210,0,255
color 10 240,0,255
color 11 270,0,255
color 12 300,0,255
color 13 330,0,255
color 14 0,0,0
color 15 0,0,0

# mode_color
mode_color 0 0 1
mode_color 0 1 11
mode_color 0 2 2
mode_color 0 3 13
mode_color 0 4 10
mode_color 0 5 3
mode_color 1 0 5
mode_color 1 1 11
mode_color 1 2 3
mode_color 1 3 13
mode_color 1 4 10
mode_color 1 5 3
mode_color 2 0 10
mode_color 2 1 11
mode_color 2 2 4
mode_color 2 3 13
mode_color 2 4 10
mode_color 2 5 3
mode_color 3 0 8
mode_color 3 1 11
mode_color 3 2 4
mode_color 3 3 13
mode_color 3 4 10
mode_color 3 5 3
mode_color 4 0 7
mode_color 4 1 11
mode_color 4 2 3
mode_color 4 3 13
mode_color 4 4 10
mode_color 4 5 3
mode_color 5 0 9
mode_color 5 1 11
mode_color 5 2 2
mode_color 5 3 13
mode_color 5 4 10
mode_color 5 5 3
mode_color 6 0 6
mode_color 6 1 10
mode_color 6 2 1
mode_color 6 3 0
mode_color 6 4 0
mode_color 6 5 2
mode_color 6 6 3
mode_color 6 7 6
mode_color 6 8 0
mode_color 6 9 0
mode_color 6 10 0

set looptime = 2000
set i2c_overclock = OFF
set gyro_sync = OFF
set gyro_sync_denom = 2
set mid_rc = 1500
set min_check = 1100
set max_check = 1900
set rssi_channel = 0
set rssi_scale = 30
set rssi_ppm_invert = OFF
set rc_smoothing = ON
set input_filtering_mode = OFF
set min_throttle = 1150
set max_throttle = 1850
set min_command = 1000
set 3d_deadband_low = 1406
set 3d_deadband_high = 1514
set 3d_neutral = 1460
set 3d_deadband_throttle = 1000
set motor_pwm_rate = 400
set motor_pwm_protocol = STANDARD
set fixed_wing_auto_arm = OFF
set disarm_kill_switch = ON
set auto_disarm_delay = 5
set small_angle = 25
set reboot_character = 82
set gps_provider = UBLOX
set gps_sbas_mode = AUTO
set gps_dyn_model = AIR_1G
set gps_auto_config = ON
set gps_auto_baud = ON
set inav_auto_mag_decl = ON
set inav_accz_unarmedcal = ON
set inav_use_gps_velned = ON
set inav_gps_delay = 200
set inav_gps_min_sats = 6
set inav_w_z_baro_p =  0.350
set inav_w_z_gps_p =  0.200
set inav_w_z_gps_v =  0.500
set inav_w_xy_gps_p =  1.000
set inav_w_xy_gps_v =  2.000
set inav_w_z_res_v =  0.500
set inav_w_xy_res_v =  0.500
set inav_w_acc_bias =  0.010
set inav_max_eph_epv =  1000.000
set inav_baro_epv =  100.000
set nav_disarm_on_landing = OFF
set nav_use_midthr_for_althold = OFF
set nav_extra_arming_safety = ON
set nav_user_control_mode = ATTI
set nav_position_timeout = 5
set nav_wp_radius = 100
set nav_max_speed = 300
set nav_max_climb_rate = 500
set nav_manual_speed = 500
set nav_manual_climb_rate = 200
set nav_landing_speed = 200
set nav_land_slowdown_minalt = 500
set nav_land_slowdown_maxalt = 2000
set nav_emerg_landing_speed = 500
set nav_min_rth_distance = 500
set nav_rth_tail_first = OFF
set nav_rth_alt_mode = AT_LEAST
set nav_rth_altitude = 1000
set nav_mc_bank_angle = 30
set nav_mc_hover_thr = 1500
set nav_mc_auto_disarm_delay = 2000
set nav_fw_cruise_thr = 1400
set nav_fw_min_thr = 1200
set nav_fw_max_thr = 1700
set nav_fw_bank_angle = 20
set nav_fw_climb_angle = 20
set nav_fw_dive_angle = 15
set nav_fw_pitch2thr = 10
set nav_fw_roll2pitch = 75
set nav_fw_loiter_radius = 5000
set serialrx_provider = SPEK1024
set spektrum_sat_bind = 0
set telemetry_switch = OFF
set telemetry_inversion = ON
set frsky_default_lattitude =  0.000
set frsky_default_longitude =  0.000
set frsky_coordinates_format = 0
set frsky_unit = IMPERIAL
set frsky_vfas_precision = 0
set hott_alarm_sound_interval = 5
set battery_capacity = 0
set vbat_scale = 110
set vbat_max_cell_voltage = 43
set vbat_min_cell_voltage = 33
set vbat_warning_cell_voltage = 35
set current_meter_scale = 400
set current_meter_offset = 0
set multiwii_current_meter_output = OFF
set current_meter_type = ADC
set align_gyro = DEFAULT
set align_acc = DEFAULT
set align_mag = DEFAULT
set align_board_roll = 0
set align_board_pitch = 0
set align_board_yaw = 0
set gyro_lpf = 42HZ
set moron_threshold = 32
set imu_dcm_kp = 2500
set imu_dcm_ki = 50
set imu_dcm_kp_mag = 10000
set imu_dcm_ki_mag = 0
set pos_hold_deadband = 20
set alt_hold_deadband = 50
set yaw_motor_direction = 1
set yaw_jump_prevention_limit = 200
set tri_unarmed_servo = ON
set servo_lowpass_freq = 400
set servo_lowpass_enable = OFF
set servo_center_pulse = 1500
set servo_pwm_rate = 50
set failsafe_delay = 10
set failsafe_off_delay = 200
set failsafe_throttle = 1000
set failsafe_kill_switch = OFF
set failsafe_throttle_low_delay = 100
set failsafe_procedure = RTH
set rx_min_usec = 885
set rx_max_usec = 2115
set acc_hardware = 0
set baro_use_median_filter = ON
set baro_hardware = 0
set mag_hardware = 0
set blackbox_rate_num = 1
set blackbox_rate_denom = 1
set blackbox_device = SDCARD
set magzero_x = 0
set magzero_y = 0
set magzero_z = 0
set acczero_x = 0
set acczero_y = 0
set acczero_z = 0
set ledstrip_visual_beeper = OFF
set accgain_x = 4096
set accgain_y = 4096
set accgain_z = 4096

# rxfail
rxfail 0 a
rxfail 1 a
rxfail 2 a
rxfail 3 a
rxfail 4 s 1400
rxfail 5 s 1000
rxfail 6 s 1000
rxfail 7 h
rxfail 8 h
rxfail 9 h
rxfail 10 h
rxfail 11 h
rxfail 12 h
rxfail 13 h
rxfail 14 h
rxfail 15 h
rxfail 16 h
rxfail 17 h

# dump profile

# profile
profile 0

# aux
aux 0 2 1 900 1200
aux 1 4 1 900 1075
aux 2 3 0 1100 1250
aux 3 3 0 1350 1475
aux 4 3 0 1600 1750
aux 5 3 0 1900 2100
aux 6 9 0 1250 1475
aux 7 9 0 1750 2100
aux 8 8 0 1500 2100
aux 9 11 1 1525 2100
aux 10 12 2 1700 2100
aux 11 17 1 1525 2100
aux 12 0 0 900 900
aux 13 0 0 900 900
aux 14 0 0 900 900
aux 15 0 0 900 900
aux 16 0 0 900 900
aux 17 0 0 900 900
aux 18 0 0 900 900
aux 19 0 0 900 900

# adjrange
adjrange 0 0 0 900 900 0 0
adjrange 1 0 0 900 900 0 0
adjrange 2 0 0 900 900 0 0
adjrange 3 0 0 900 900 0 0
adjrange 4 0 0 900 900 0 0
adjrange 5 0 0 900 900 0 0
adjrange 6 0 0 900 900 0 0
adjrange 7 0 0 900 900 0 0
adjrange 8 0 0 900 900 0 0
adjrange 9 0 0 900 900 0 0
adjrange 10 0 0 900 900 0 0
adjrange 11 2 2 900 2100 12 2

# rxrange
rxrange 0 1000 2000
rxrange 1 1000 2000
rxrange 2 1000 2000
rxrange 3 1000 2000

# servo
servo 0 1000 2000 1500 90 90 100 -1
servo 1 1000 2000 1500 90 90 100 -1
servo 2 1000 2000 1500 90 90 100 -1
servo 3 1000 2000 1500 90 90 100 -1
servo 4 1000 2000 1500 90 90 100 -1
servo 5 1000 2000 1500 90 90 100 -1
servo 6 1000 2000 1500 90 90 100 -1
servo 7 1000 2000 1500 90 90 100 -1

set nav_alt_p = 50
set nav_alt_i = 0
set nav_alt_d = 0
set nav_vel_p = 100
set nav_vel_i = 50
set nav_vel_d = 10
set nav_pos_p = 65
set nav_pos_i = 120
set nav_pos_d = 10
set nav_posr_p = 180
set nav_posr_i = 15
set nav_posr_d = 100
set nav_navr_p = 10
set nav_navr_i = 5
set nav_navr_d = 8
set deadband = 5
set yaw_deadband = 5
set throttle_tilt_comp_str = 0
set flaperon_throw_offset = 250
set flaperon_throw_inverted = OFF
set gimbal_mode = NORMAL
set fw_iterm_throw_limit = 165
set mode_range_logic_operator = OR
set default_rate_profile = 0
set mag_declination = 0
set mag_hold_rate_limit = 90
set p_pitch = 40
set i_pitch = 30
set d_pitch = 23
set p_roll = 40
set i_roll = 30
set d_roll = 23
set p_yaw = 85
set i_yaw = 45
set d_yaw = 0
set p_level = 20
set i_level = 15
set d_level = 75
set max_angle_inclination_rll = 300
set max_angle_inclination_pit = 300
set gyro_soft_lpf_hz = 60
set acc_soft_lpf_hz = 15
set dterm_lpf_hz = 40
set yaw_lpf_hz = 30
set yaw_p_limit = 300
set iterm_ignore_threshold = 200
set yaw_iterm_ignore_threshold = 50
set rate_accel_limit_roll_pitch = 0
set rate_accel_limit_yaw = 10000

# dump rates

# rateprofile
rateprofile 0

set rc_expo = 70
set rc_yaw_expo = 20
set thr_mid = 50
set thr_expo = 0
set roll_rate = 40
set pitch_rate = 40
set yaw_rate = 40
set tpa_rate = 0
set tpa_breakpoint = 1500

# 
digitalentity commented 8 years ago

Actually, I've looked at the code and channel forwarding is only supported on NAZE and origianl SPRacingF3. So far EVO is not supporting the feature.

digitalentity commented 8 years ago

We can enable channel forwarding on S7 asnd S8 outputs, but this will effectively limit multirotor setups with servos to 4 motors due to hardware limitations.

krzysztofmatula commented 8 years ago

If it's hardware limitation we must live with it... 4+2 or 8+0 switchable by CHANNEL_FORWARDING feature is still much better than no servo support at all.

digitalentity commented 8 years ago

@hydra, as a designer of SPRacingF3 family maybe you can give us a clue how to get channel forwarding working on EVO?

mifan1 commented 8 years ago

I found that in older version CF/BTFL is diference between F1 and F3 with SERVO_TILT :

hydra commented 8 years ago

@mifan1 it's not specifically ALL F3 targets, it's dependent on the timer configuration and PWM mapping code. Servos need a different time to motor outputs.

EVO:

    { TIM8,  GPIOA, Pin_15, TIM_Channel_1, TIM8_CC_IRQn,            0, Mode_AF_PP_PD, GPIO_PinSource15, GPIO_AF_2},  // PPM

    { TIM2,  GPIOA, Pin_0,  TIM_Channel_1, TIM2_IRQn,               1, Mode_AF_PP, GPIO_PinSource0,  GPIO_AF_1},  // PWM1
    { TIM2,  GPIOA, Pin_1,  TIM_Channel_2, TIM2_IRQn,               1, Mode_AF_PP, GPIO_PinSource1,  GPIO_AF_1},  // PWM2
    { TIM15, GPIOA, Pin_2,  TIM_Channel_1, TIM1_BRK_TIM15_IRQn,     1, Mode_AF_PP, GPIO_PinSource2,  GPIO_AF_9},  // PWM3
    { TIM15, GPIOA, Pin_3,  TIM_Channel_2, TIM1_BRK_TIM15_IRQn,     1, Mode_AF_PP, GPIO_PinSource3,  GPIO_AF_9},  // PWM4
    { TIM3,  GPIOA, Pin_6,  TIM_Channel_1, TIM3_IRQn,               1, Mode_AF_PP, GPIO_PinSource6,  GPIO_AF_2},  // PWM5
    { TIM3,  GPIOA, Pin_7,  TIM_Channel_2, TIM3_IRQn,               1, Mode_AF_PP, GPIO_PinSource7,  GPIO_AF_2},  // PWM6
    { TIM3,  GPIOB, Pin_0,  TIM_Channel_3, TIM3_IRQn,               1, Mode_AF_PP, GPIO_PinSource0,  GPIO_AF_2},  // PWM7
    { TIM3,  GPIOB, Pin_1,  TIM_Channel_4, TIM3_IRQn,               1, Mode_AF_PP, GPIO_PinSource1,  GPIO_AF_2},  // PWM8
#if defined(SPRACINGF3EVO)
            // remap PWM8+9 as servos
            if ((timerIndex == PWM8 || timerIndex == PWM9) && timerHardwarePtr->tim == TIM3)
                type = MAP_TO_SERVO_OUTPUT;
#endif

you have to ignore the comments on the timer.c code. but basically ESC outputs 7+8 should be used as servos.

TIM3 is also used for softserial 1/2 IIRC.

The pwm mapping code could be updated to use ESC outputs 5,6,7 & 8 to drive 4 servos or updated so that ESC 1/2 are servo outputs and 3 onwards are for motor/softserial.

csarka commented 8 years ago

So, the RMDO would be the same configuration?

hydra commented 8 years ago

Ask RMRC.

hydra commented 8 years ago

@digitalentity the channel forwarding is here:


        if (init->useChannelForwarding && !init->airplane) {
#if defined(NAZE) && defined(LED_STRIP_TIMER)
            // if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14
            if (init->useLEDStrip) { 
                if (timerIndex >= PWM13 && timerIndex <= PWM14) {
                  type = MAP_TO_SERVO_OUTPUT;
                }
            } else
#endif

#if defined(SPRACINGF3) || defined(NAZE)
                // remap PWM5..8 as servos when used in extended servo mode
                if (timerIndex >= PWM5 && timerIndex <= PWM8)
                    type = MAP_TO_SERVO_OUTPUT;
#endif
        }

gosh I hate pwm_mapping.c it's such a hack.

hydra commented 8 years ago

you also have to look at the pwm map that is used, the amount of servos used by the mixer and then you might just be able to figure out on which pin a forwarded channel might end up on. good luck! 😄

digitalentity commented 8 years ago

So basically, we have channel forwarding only for SPRF3 and NAZE, that's a problem. We need more targets supporting this.

On EVO TIM3 can probably be used for channel forwarding (4 channel) - outputs 4-8 will be servo channels.

hydra commented 8 years ago

yeah, i'm fixing it here, 1 sec.

hydra commented 8 years ago

really, all unused motor outputs should just be remapped to servos i think.

hydra commented 8 years ago

oh gosh. I'm not touching that code right now. Gonna wait for the BF changes to fix it. @blkmn was working on it.

Basically there needs to be a proper way of allocating pins so we can delete all this horrid and fragile mapping code.

hydra commented 8 years ago

channel forwarding will be used on the first available servo pin, IIRC. The code above just assigns extra pins on the NAZE and SP Racing F3 - both of those boards have 8 channel PWM input. When the mapping is a PPM input the PWM inputs are free to be used as outputs. The EVO and other boards do not need that code to run because they don't have any used PWM input pins.

digitalentity commented 8 years ago

I'm not sure any code change can fix it. We are limited by timers - they have different base frequency for pwm/oneshot/etc. Basically, if it wasn't considered during HW design phase - our choices are very limited.

hydra commented 8 years ago

agreed. it's why I specifically grouped the pins in pairs and 4's on the the SP Racing boards.

Unlike the Sparky and CC3D which have pins and timers all over the place.

digitalentity commented 8 years ago

I totally agree - pwm_mapping.c is a huge messy pile of junk. Can't wait for somebody to clean it up. If @blckmn is on it - I'll wait for his change as well. We don't need 3 implementations of the same thing.

digitalentity commented 8 years ago

CC3D is one messiest board I've hacked, but it's dirt cheap and pretty functional.

hydra commented 8 years ago

i think we might be able to do this:

        if ((init->useServos || init->useChannelForwarding) && !init->airplane) {

as a quick workaround. gonna have a little look, but if it starts taking too long I'm backing out.

hydra commented 8 years ago

yeah, that seems to work. e.g.

SPRACINGF3EVO, Tricopter + channel forwarding. ESC1-3 = motors, ESC5 = servo ESC6/7/8 = AUX1/2/3

digitalentity commented 8 years ago

This might affect other targets. I'll test, thanks for suggestion.

hydra commented 8 years ago

Yeah, I don't see the harm in the change though. I'll merge that in CF now and people can do some testing in the next RC.

hydra commented 8 years ago

In looking at this it appears there's more bugs in the code. No point me duplicating @blckmn 's code and effort right now.

hydra commented 8 years ago

The pwm mapping code is not aware of how many actual servos and actual motors it needs. And that is the fundamental problem. Nor is it aware of the order in which timers and channels should be allocated for motors/servos. It should also know about which other pins the user has allocated - e.g. for sonar, ppm, pwm, softserial, etc.

If you had that information, on a per-target basis, then the code could probably be a LOT simpler. any references to airplane and dependencies on other subsystems would the be able to be removed entirely.

And all the target specific could would also be able to be removed.

blckmn commented 8 years ago

We've just merged the resource io code in BF3.1 (development branch). You can now assign any timer mapping (for any target) to servo output. I've yet to test if channel forwarding works.

blckmn commented 8 years ago

https://github.com/betaflight/betaflight/pull/1189 First comment has the instructions on use.

blckmn commented 8 years ago

@hydra the mapping to actual use is now done by the user and stored in configuration. The pwm mapping code is effectively removed. The target has the opportunity to map its default working configuration on reset in a target specific config, or it goes by the default output order in timer mapping (based on function).

It will require effort in the Configurator at some point in the future for potential quick config scenarios per target, and warnings on resource conflicts.

blckmn commented 8 years ago

By quick config scenarios I mean Quad Racer, Airplane, Tricopter etc

hydra commented 8 years ago

@blckmn yeah, I'm looking forward to seeing that.

@digitalentity and others - see these two commits

94256215f19c577f8a86d4650b4a5933ae6f0eca 696d5d919310d8ac9c443654aafbeda06dca56d3

I figured I'd take the safest approach and only risk breaking two targets 😄

Channel forwarding/servo allocation takes precedence over motor outputs so if your mixer uses more than four motors then enabling channel forwarding when using more than 4 motors is not supported right now. This is probably OK for most people. Users of Hex/Y6/etc just can't use channel forwarding so not a deal breaker considering the usage of those craft.

krzysztofmatula commented 8 years ago

I checked those 2 commits and I can only say they work great :) I have 400Hz PWM on M1-M4 and 50Hz on M5-M8 with AUX 1-4 values forwarded.