mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
tap: add landing gear capability
This configures the PWM output for the landing gear.
This commit is contained in:
parent
2fff2ab9ac
commit
78b0d1a01f
@ -23,5 +23,5 @@ S: 0 7 0 20000 -10000 -10000 10000
|
||||
# mixer for right leg
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 8 0 20000 -10000 -10000 10000
|
||||
S: 0 7 0 20000 -10000 -10000 10000
|
||||
|
||||
|
||||
@ -331,10 +331,20 @@ unset OUTPUT_MODE
|
||||
#
|
||||
# Start the RC input driver
|
||||
#
|
||||
if fmu mode_rcin
|
||||
if fmu mode_pwm1
|
||||
then
|
||||
fi
|
||||
|
||||
#
|
||||
# Use 400 Hz PWM output for landing gear (frequency also affects RGB LED)
|
||||
#
|
||||
pwm rate -c 1 -r 400
|
||||
|
||||
#
|
||||
# Load the gear mixer onto fmu
|
||||
#
|
||||
mixer load /dev/px4fmu /etc/mixers/gear.mix
|
||||
|
||||
#
|
||||
# Start the navigator
|
||||
#
|
||||
|
||||
7
ROMFS/tap_common/mixers/gear.mix
Normal file
7
ROMFS/tap_common/mixers/gear.mix
Normal file
@ -0,0 +1,7 @@
|
||||
#
|
||||
# This maps actuator_controls_0[7] to the first and only PWM output
|
||||
#
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 7 10000 10000 0 -10000 10000
|
||||
@ -195,11 +195,19 @@ __BEGIN_DECLS
|
||||
#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_1
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 4
|
||||
|
||||
#define GPIO_TIM3_CH1IN GPIO_TIM3_CH1IN_1
|
||||
#define GPIO_TIM3_CH2IN GPIO_TIM3_CH2IN_1
|
||||
#define GPIO_TIM3_CH3IN GPIO_TIM3_CH3IN_1
|
||||
#define GPIO_TIM3_CH4IN GPIO_TIM3_CH4IN_1
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 4
|
||||
|
||||
#define BOARD_HAS_LED_PWM
|
||||
#define LED_TIM3_CH1OUT GPIO_TIM3_CH1OUT
|
||||
#define LED_TIM3_CH2OUT GPIO_TIM3_CH2OUT
|
||||
#define LED_TIM3_CH3OUT GPIO_TIM3_CH3OUT
|
||||
|
||||
#define BOARD_PWM_DRIVE_ACTIVE_LOW 1
|
||||
|
||||
|
||||
/* USB OTG FS
|
||||
*
|
||||
|
||||
@ -58,40 +58,16 @@ __EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
.clock_bit = RCC_APB1ENR_TIM3EN,
|
||||
.clock_freq = STM32_APB1_TIM3_CLKIN,
|
||||
.first_channel_index = 0,
|
||||
.last_channel_index = 3,
|
||||
.last_channel_index = 0,
|
||||
.handler = io_timer_handler0,
|
||||
.vectorno = STM32_IRQ_TIM3,
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH1OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH2OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH3OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH4OUT,
|
||||
.gpio_in = 0,
|
||||
.gpio_in = GPIO_TIM3_CH4IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 4,
|
||||
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
|
||||
|
||||
@ -261,16 +261,17 @@ struct pwm_output_rc_config {
|
||||
|
||||
/** set auxillary output mode. These correspond to enum Mode in px4fmu/fmu.cpp */
|
||||
#define PWM_SERVO_MODE_NONE 0
|
||||
#define PWM_SERVO_MODE_2PWM 1
|
||||
#define PWM_SERVO_MODE_2PWM2CAP 2
|
||||
#define PWM_SERVO_MODE_3PWM 3
|
||||
#define PWM_SERVO_MODE_3PWM1CAP 4
|
||||
#define PWM_SERVO_MODE_4PWM 5
|
||||
#define PWM_SERVO_MODE_6PWM 6
|
||||
#define PWM_SERVO_MODE_8PWM 7
|
||||
#define PWM_SERVO_MODE_4CAP 8
|
||||
#define PWM_SERVO_MODE_5CAP 9
|
||||
#define PWM_SERVO_MODE_6CAP 10
|
||||
#define PWM_SERVO_MODE_1PWM 1
|
||||
#define PWM_SERVO_MODE_2PWM 2
|
||||
#define PWM_SERVO_MODE_2PWM2CAP 3
|
||||
#define PWM_SERVO_MODE_3PWM 4
|
||||
#define PWM_SERVO_MODE_3PWM1CAP 5
|
||||
#define PWM_SERVO_MODE_4PWM 6
|
||||
#define PWM_SERVO_MODE_6PWM 7
|
||||
#define PWM_SERVO_MODE_8PWM 8
|
||||
#define PWM_SERVO_MODE_4CAP 9
|
||||
#define PWM_SERVO_MODE_5CAP 10
|
||||
#define PWM_SERVO_MODE_6CAP 11
|
||||
#define PWM_SERVO_SET_MODE _PX4_IOC(_PWM_SERVO_BASE, 32)
|
||||
|
||||
/*
|
||||
|
||||
@ -116,6 +116,7 @@ class PX4FMU : public device::CDev
|
||||
public:
|
||||
enum Mode {
|
||||
MODE_NONE,
|
||||
MODE_1PWM,
|
||||
MODE_2PWM,
|
||||
MODE_2PWM2CAP,
|
||||
MODE_3PWM,
|
||||
@ -529,6 +530,15 @@ PX4FMU::set_mode(Mode mode)
|
||||
* are presented on the output pins.
|
||||
*/
|
||||
switch (mode) {
|
||||
case MODE_1PWM:
|
||||
/* default output rates */
|
||||
_pwm_default_rate = 50;
|
||||
_pwm_alt_rate = 50;
|
||||
_pwm_alt_rate_channels = 0;
|
||||
_pwm_mask = 0x1;
|
||||
_pwm_initialized = false;
|
||||
break;
|
||||
|
||||
case MODE_2PWM2CAP: // v1 multi-port with flow control lines as PWM
|
||||
up_input_capture_set(2, Rising, 0, NULL, NULL);
|
||||
up_input_capture_set(3, Rising, 0, NULL, NULL);
|
||||
@ -1041,6 +1051,10 @@ PX4FMU::cycle()
|
||||
size_t num_outputs;
|
||||
|
||||
switch (_mode) {
|
||||
case MODE_1PWM:
|
||||
num_outputs = 1;
|
||||
break;
|
||||
|
||||
case MODE_2PWM:
|
||||
case MODE_2PWM2CAP:
|
||||
num_outputs = 2;
|
||||
@ -1588,6 +1602,7 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
|
||||
|
||||
/* if we are in valid PWM mode, try it as a PWM ioctl as well */
|
||||
switch (_mode) {
|
||||
case MODE_1PWM:
|
||||
case MODE_2PWM:
|
||||
case MODE_3PWM:
|
||||
case MODE_4PWM:
|
||||
@ -2002,6 +2017,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
*(unsigned *)arg = 2;
|
||||
break;
|
||||
|
||||
case MODE_1PWM:
|
||||
*(unsigned *)arg = 1;
|
||||
break;
|
||||
|
||||
default:
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
@ -2022,6 +2041,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
set_mode(MODE_NONE);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
set_mode(MODE_1PWM);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
set_mode(MODE_2PWM);
|
||||
break;
|
||||
@ -2062,6 +2085,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
||||
ret = set_mode(MODE_NONE);
|
||||
break;
|
||||
|
||||
case PWM_SERVO_MODE_1PWM:
|
||||
ret = set_mode(MODE_1PWM);
|
||||
break;
|
||||
|
||||
case PWM_SERVO_MODE_2PWM:
|
||||
ret = set_mode(MODE_2PWM);
|
||||
break;
|
||||
@ -2616,6 +2643,7 @@ enum PortMode {
|
||||
PORT_PWM4,
|
||||
PORT_PWM3,
|
||||
PORT_PWM2,
|
||||
PORT_PWM1,
|
||||
PORT_PWM3CAP1,
|
||||
PORT_PWM2CAP2,
|
||||
PORT_CAPTURE,
|
||||
@ -2639,6 +2667,12 @@ fmu_new_mode(PortMode new_mode)
|
||||
break;
|
||||
|
||||
case PORT_FULL_PWM:
|
||||
|
||||
case PORT_PWM1:
|
||||
/* select 2-pin PWM mode */
|
||||
servo_mode = PX4FMU::MODE_1PWM;
|
||||
break;
|
||||
|
||||
#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM == 4
|
||||
/* select 4-pin PWM mode */
|
||||
servo_mode = PX4FMU::MODE_4PWM;
|
||||
@ -3092,7 +3126,14 @@ fmu_main(int argc, char *argv[])
|
||||
} else if (!strcmp(verb, "mode_pwm")) {
|
||||
new_mode = PORT_FULL_PWM;
|
||||
|
||||
#if defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 6
|
||||
#if defined(BOARD_HAS_PWM)
|
||||
|
||||
} else if (!strcmp(verb, "mode_pwm1")) {
|
||||
new_mode = PORT_PWM1;
|
||||
|
||||
|
||||
#elif defined(BOARD_HAS_PWM) && BOARD_HAS_PWM >= 6
|
||||
|
||||
|
||||
} else if (!strcmp(verb, "mode_pwm4")) {
|
||||
new_mode = PORT_PWM4;
|
||||
|
||||
@ -394,7 +394,7 @@ static int timer_set_rate(unsigned timer, unsigned rate)
|
||||
}
|
||||
|
||||
|
||||
static int io_timer_init_timer(unsigned timer)
|
||||
int io_timer_init_timer(unsigned timer)
|
||||
{
|
||||
/* Do this only once per timer */
|
||||
|
||||
@ -708,6 +708,10 @@ int io_timer_set_ccr(unsigned channel, uint16_t value)
|
||||
} else {
|
||||
|
||||
/* configure the channel */
|
||||
#ifdef BOARD_PWM_DRIVE_ACTIVE_LOW
|
||||
unsigned period = rARR(channels_timer(channel));
|
||||
value = period - value;
|
||||
#endif
|
||||
|
||||
if (value > 0) {
|
||||
value--;
|
||||
@ -727,6 +731,12 @@ uint16_t io_channel_get_ccr(unsigned channel)
|
||||
if (io_timer_validate_channel_index(channel) == 0 &&
|
||||
io_timer_get_channel_mode(channel) == IOTimerChanMode_PWMOut) {
|
||||
value = REG(channels_timer(channel), timer_io_channels[channel].ccr_offset) + 1;
|
||||
|
||||
#ifdef BOARD_PWM_DRIVE_ACTIVE_LOW
|
||||
unsigned period = rARR(channels_timer(channel));
|
||||
value = period - value;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
return value;
|
||||
|
||||
@ -106,6 +106,9 @@ __EXPORT int io_timer_handler3(int irq, void *context);
|
||||
|
||||
__EXPORT int io_timer_channel_init(unsigned channel, io_timer_channel_mode_t mode,
|
||||
channel_handler_t channel_handler, void *context);
|
||||
|
||||
__EXPORT int io_timer_init_timer(unsigned timer);
|
||||
|
||||
__EXPORT int io_timer_set_rate(unsigned timer, unsigned rate);
|
||||
__EXPORT int io_timer_set_enable(bool state, io_timer_channel_mode_t mode,
|
||||
io_timer_channel_allocation_t masks);
|
||||
|
||||
@ -85,8 +85,9 @@
|
||||
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
|
||||
#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
|
||||
|
||||
static void led_pwm_timer_init(unsigned timer);
|
||||
static void led_pwm_timer_set_rate(unsigned timer, unsigned rate);
|
||||
|
||||
extern int io_timer_init_timer(unsigned timer);
|
||||
|
||||
static void led_pwm_channel_init(unsigned channel);
|
||||
|
||||
int led_pwm_servo_set(unsigned channel, uint8_t value);
|
||||
@ -97,56 +98,11 @@ void led_pwm_servo_arm(bool armed);
|
||||
unsigned led_pwm_timer_get_period(unsigned timer);
|
||||
|
||||
|
||||
static void
|
||||
led_pwm_timer_init(unsigned timer)
|
||||
{
|
||||
/* valid Timer */
|
||||
|
||||
if (led_pwm_timers[timer].base != 0) {
|
||||
|
||||
/* enable the timer clock before we try to talk to it */
|
||||
|
||||
modifyreg32(led_pwm_timers[timer].clock_register, 0, led_pwm_timers[timer].clock_bit);
|
||||
|
||||
/* disable and configure the timer */
|
||||
rCR1(timer) = 0;
|
||||
rCR2(timer) = 0;
|
||||
rSMCR(timer) = 0;
|
||||
rDIER(timer) = 0;
|
||||
rCCER(timer) = 0;
|
||||
rCCMR1(timer) = 0;
|
||||
rCCMR2(timer) = 0;
|
||||
rCCER(timer) = 0;
|
||||
rDCR(timer) = 0;
|
||||
|
||||
if ((led_pwm_timers[timer].base == STM32_TIM1_BASE) || (led_pwm_timers[timer].base == STM32_TIM8_BASE)) {
|
||||
/* master output enable = on */
|
||||
rBDTR(timer) = ATIM_BDTR_MOE;
|
||||
}
|
||||
|
||||
/* configure the timer to free-run at 1MHz */
|
||||
rPSC(timer) = (led_pwm_timers[timer].clock_freq / 1000000) - 1;
|
||||
|
||||
/* default to updating at 50Hz */
|
||||
led_pwm_timer_set_rate(timer, 50);
|
||||
|
||||
/* note that the timer is left disabled - arming is performed separately */
|
||||
}
|
||||
}
|
||||
unsigned
|
||||
led_pwm_timer_get_period(unsigned timer)
|
||||
{
|
||||
return (rARR(timer));
|
||||
}
|
||||
static void
|
||||
led_pwm_timer_set_rate(unsigned timer, unsigned rate)
|
||||
{
|
||||
/* configure the timer to update at the desired rate */
|
||||
rARR(timer) = 1000000 / rate;
|
||||
|
||||
/* generate an update event; reloads the counter and all registers */
|
||||
rEGR(timer) = GTIM_EGR_UG;
|
||||
}
|
||||
|
||||
|
||||
static void
|
||||
@ -277,7 +233,7 @@ led_pwm_servo_init(void)
|
||||
{
|
||||
/* do basic timer initialisation first */
|
||||
for (unsigned i = 0; i < arraySize(led_pwm_timers); i++) {
|
||||
led_pwm_timer_init(i);
|
||||
io_timer_init_timer(i);
|
||||
}
|
||||
|
||||
/* now init channels */
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user