mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
Allowing oneshot125 functionality to work on a Naze board.
This code has been flight tested, but will have problems on a CC3D board, and also when the looptime is longer than 8200 uS.
This commit is contained in:
parent
f5a579de14
commit
94c5573c39
6 changed files with 37 additions and 4 deletions
|
@ -39,7 +39,8 @@ typedef enum {
|
||||||
FEATURE_RX_MSP = 1 << 14,
|
FEATURE_RX_MSP = 1 << 14,
|
||||||
FEATURE_RSSI_ADC = 1 << 15,
|
FEATURE_RSSI_ADC = 1 << 15,
|
||||||
FEATURE_LED_STRIP = 1 << 16,
|
FEATURE_LED_STRIP = 1 << 16,
|
||||||
FEATURE_DISPLAY = 1 << 17
|
FEATURE_DISPLAY = 1 << 17,
|
||||||
|
FEATURE_ONESHOT125 = 1 << 18
|
||||||
} features_e;
|
} features_e;
|
||||||
|
|
||||||
bool feature(uint32_t mask);
|
bool feature(uint32_t mask);
|
||||||
|
|
|
@ -34,6 +34,7 @@
|
||||||
#define MAX_INPUTS 8
|
#define MAX_INPUTS 8
|
||||||
|
|
||||||
#define PWM_TIMER_MHZ 1
|
#define PWM_TIMER_MHZ 1
|
||||||
|
#define ONESHOT125_TIMER_MHZ 8
|
||||||
|
|
||||||
typedef struct drv_pwm_config_t {
|
typedef struct drv_pwm_config_t {
|
||||||
bool useParallelPWM;
|
bool useParallelPWM;
|
||||||
|
|
|
@ -27,6 +27,8 @@
|
||||||
|
|
||||||
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
|
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
|
||||||
|
|
||||||
|
#include "config/config.h" // FIXME dependency into the main code from a driver
|
||||||
|
|
||||||
#include "pwm_mapping.h"
|
#include "pwm_mapping.h"
|
||||||
|
|
||||||
#include "pwm_output.h"
|
#include "pwm_output.h"
|
||||||
|
@ -35,6 +37,7 @@ typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function poi
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
volatile timCCR_t *ccr;
|
volatile timCCR_t *ccr;
|
||||||
|
volatile timCNT_t *cnt;
|
||||||
uint16_t period;
|
uint16_t period;
|
||||||
pwmWriteFuncPtr pwmWritePtr;
|
pwmWriteFuncPtr pwmWritePtr;
|
||||||
} pwmOutputPort_t;
|
} pwmOutputPort_t;
|
||||||
|
@ -43,6 +46,7 @@ static pwmOutputPort_t pwmOutputPorts[MAX_PWM_OUTPUT_PORTS];
|
||||||
|
|
||||||
static pwmOutputPort_t *motors[MAX_PWM_MOTORS];
|
static pwmOutputPort_t *motors[MAX_PWM_MOTORS];
|
||||||
static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
|
static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
|
||||||
|
static volatile uint16_t* lastCounterPtr;
|
||||||
|
|
||||||
#define PWM_BRUSHED_TIMER_MHZ 8
|
#define PWM_BRUSHED_TIMER_MHZ 8
|
||||||
|
|
||||||
|
@ -116,6 +120,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
p->period = period;
|
p->period = period;
|
||||||
|
p->cnt = &timerHardware->tim->CNT;
|
||||||
|
|
||||||
return p;
|
return p;
|
||||||
}
|
}
|
||||||
|
@ -127,7 +132,7 @@ static void pwmWriteBrushed(uint8_t index, uint16_t value)
|
||||||
|
|
||||||
static void pwmWriteStandard(uint8_t index, uint16_t value)
|
static void pwmWriteStandard(uint8_t index, uint16_t value)
|
||||||
{
|
{
|
||||||
*motors[index]->ccr = value;
|
*motors[index]->ccr = value;
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmWriteMotor(uint8_t index, uint16_t value)
|
void pwmWriteMotor(uint8_t index, uint16_t value)
|
||||||
|
@ -136,6 +141,23 @@ void pwmWriteMotor(uint8_t index, uint16_t value)
|
||||||
motors[index]->pwmWritePtr(index, value);
|
motors[index]->pwmWritePtr(index, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void pwmFinishedWritingMotors(uint8_t numberMotors)
|
||||||
|
{
|
||||||
|
uint8_t index;
|
||||||
|
|
||||||
|
if(feature(FEATURE_ONESHOT125)){
|
||||||
|
|
||||||
|
for(index = 0; index < numberMotors; index++){
|
||||||
|
// Set the counter to overflow if it's the first motor to output, or if we change timers
|
||||||
|
if((index == 0) || (motors[index]->cnt != lastCounterPtr)){
|
||||||
|
lastCounterPtr = motors[index]->cnt;
|
||||||
|
|
||||||
|
*motors[index]->cnt = 0xfffe;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void pwmWriteServo(uint8_t index, uint16_t value)
|
void pwmWriteServo(uint8_t index, uint16_t value)
|
||||||
{
|
{
|
||||||
if (servos[index] && index < MAX_SERVOS)
|
if (servos[index] && index < MAX_SERVOS)
|
||||||
|
@ -154,7 +176,13 @@ void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIn
|
||||||
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
|
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
|
||||||
{
|
{
|
||||||
uint32_t hz = PWM_TIMER_MHZ * 1000000;
|
uint32_t hz = PWM_TIMER_MHZ * 1000000;
|
||||||
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse);
|
|
||||||
|
if(feature(FEATURE_ONESHOT125)){
|
||||||
|
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, 0xFFFF, idlePulse);
|
||||||
|
} else {
|
||||||
|
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse);
|
||||||
|
}
|
||||||
|
|
||||||
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -20,6 +20,7 @@
|
||||||
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||||
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||||
void pwmWriteMotor(uint8_t index, uint16_t value);
|
void pwmWriteMotor(uint8_t index, uint16_t value);
|
||||||
|
void pwmFinishedWritingMotors(uint8_t numberMotors);
|
||||||
|
|
||||||
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
|
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
|
||||||
void pwmWriteServo(uint8_t index, uint16_t value);
|
void pwmWriteServo(uint8_t index, uint16_t value);
|
||||||
|
|
|
@ -395,6 +395,8 @@ void writeMotors(void)
|
||||||
|
|
||||||
for (i = 0; i < numberMotor; i++)
|
for (i = 0; i < numberMotor; i++)
|
||||||
pwmWriteMotor(i, motor[i]);
|
pwmWriteMotor(i, motor[i]);
|
||||||
|
|
||||||
|
pwmFinishedWritingMotors(numberMotor);
|
||||||
}
|
}
|
||||||
|
|
||||||
void writeAllMotors(int16_t mc)
|
void writeAllMotors(int16_t mc)
|
||||||
|
|
|
@ -123,7 +123,7 @@ static const char * const featureNames[] = {
|
||||||
"RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
|
"RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
|
||||||
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
|
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
|
||||||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", NULL
|
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", NULL
|
||||||
};
|
};
|
||||||
|
|
||||||
// sync this with sensors_e
|
// sync this with sensors_e
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue