HAL_F4Light fixes: removed unused code, removed debugging printf(), removed hard-coded pins

This commit is contained in:
night-ghost 2018-04-26 15:15:03 +05:00 committed by Andrew Tridgell
parent e5c3fd43ee
commit a2cc54fb5d
8 changed files with 86 additions and 120 deletions

View File

@ -274,7 +274,9 @@ uint16_t RCInput::read(uint8_t ch)
if(!fs_flag) { if(!fs_flag) {
fs_flag=true; fs_flag=true;
#ifdef DEBUG_BUILD
printf("\n failsafe! now=%lld last pulse=%lld last change=%lld\n",now, pulse, last); printf("\n failsafe! now=%lld last pulse=%lld last change=%lld\n",now, pulse, last);
#endif
} }
} else { } else {
fs_flag=false; fs_flag=false;
@ -288,7 +290,9 @@ uint16_t RCInput::read(uint8_t ch)
if(last_4 < 990 && data >1300 && data < 1700){ if(last_4 < 990 && data >1300 && data < 1700){
if(!aibao_fs_flag){ if(!aibao_fs_flag){
aibao_fs_flag=true; aibao_fs_flag=true;
#ifdef DEBUG_BUILD
printf("\nAibao failsafe! ch4=%d ch2=%d\n",last_4, data); printf("\nAibao failsafe! ch4=%d ch2=%d\n",last_4, data);
#endif
} }
data = 901; // to know the source data = 901; // to know the source
} else { } else {

View File

@ -23,6 +23,37 @@ using namespace F4Light;
#define F4Light_OUT_CHANNELS 6 // motor's channels enabled by default #define F4Light_OUT_CHANNELS 6 // motor's channels enabled by default
#ifndef SERVO_PIN_5
#define SERVO_PIN_5 ((uint8_t)-1)
#endif
#ifndef SERVO_PIN_6
#define SERVO_PIN_6 ((uint8_t)-1)
#endif
#ifndef SERVO_PIN_7
#define SERVO_PIN_7 ((uint8_t)-1)
#endif
#ifndef SERVO_PIN_8
#define SERVO_PIN_8 ((uint8_t)-1)
#endif
#ifndef SERVO_PIN_9
#define SERVO_PIN_9 ((uint8_t)-1)
#endif
#ifndef SERVO_PIN_10
#define SERVO_PIN_10 ((uint8_t)-1)
#endif
#ifndef SERVO_PIN_11
#define SERVO_PIN_11 ((uint8_t)-1)
#endif
// #if FRAME_CONFIG == QUAD_FRAME // this is only QUAD layouts // #if FRAME_CONFIG == QUAD_FRAME // this is only QUAD layouts
// ArduCopter // ArduCopter
@ -31,20 +62,15 @@ static const uint8_t output_channels_arducopter[]= { // pin assignment
SERVO_PIN_2, //Timer3/4 - 2 SERVO_PIN_2, //Timer3/4 - 2
SERVO_PIN_3, //Timer2/3 - 3 SERVO_PIN_3, //Timer2/3 - 3
SERVO_PIN_4, //Timer2/2 - 4 SERVO_PIN_4, //Timer2/2 - 4
#ifdef SERVO_PIN_5 SERVO_PIN_5,
SERVO_PIN_5, //Timer2/1 SERVO_PIN_6,
#endif
#ifdef SERVO_PIN_6
SERVO_PIN_6, //Timer2/0
#endif
// servo channels on input port // servo channels on input port
4, // PB14 CH1_IN - PPM1 Use this channels asd servo only if you use DSM via UART as RC SERVO_PIN_7, // PB15 CH2_IN - PPM2
5, // PB15 CH2_IN - PPM2 SERVO_PIN_8, // PC6 CH3_IN UART6
12, // PC6 CH3_IN UART6 SERVO_PIN_9, // PC7 CH4_IN UART6
13, // PC7 CH4_IN UART6 SERVO_PIN_10, // PC8 CH5_IN i2c
14, // PC8 CH5_IN i2c SERVO_PIN_11, // PC9 CH6_IN i2c
15, // PC9 CH6_IN i2c
}; };
@ -56,20 +82,15 @@ static const uint8_t output_channels_openpilot[]= { // pin assignment
SERVO_PIN_4, //Timer2/2 - 4 SERVO_PIN_4, //Timer2/2 - 4
SERVO_PIN_1, //Timer3/3 - 1 SERVO_PIN_1, //Timer3/3 - 1
SERVO_PIN_3, //Timer2/3 - 3 SERVO_PIN_3, //Timer2/3 - 3
#ifdef SERVO_PIN_5
SERVO_PIN_5, //Timer2/1 SERVO_PIN_5, //Timer2/1
#endif
#ifdef SERVO_PIN_6
SERVO_PIN_6, //Timer2/0 SERVO_PIN_6, //Timer2/0
#endif
// servo channels on input port // servo channels on input port
// 4, // PB14 CH1_IN - PPM1 Use this channels asd servo only if you use DSM via UART as RC SERVO_PIN_7, // PB15 CH2_IN - PPM2
5, // PB15 CH2_IN - PPM2 SERVO_PIN_8, // PC6 CH3_IN UART6
12, // PC6 CH3_IN UART6 SERVO_PIN_9, // PC7 CH4_IN UART6
13, // PC7 CH4_IN UART6 SERVO_PIN_10, // PC8 CH5_IN i2c
14, // PC8 CH5_IN i2c SERVO_PIN_11, // PC9 CH6_IN i2c
15, // PC9 CH6_IN i2c
}; };
@ -79,43 +100,32 @@ static const uint8_t output_channels_cleanflight[]= { // pin assignment
SERVO_PIN_3, //Timer2/3 - 3 SERVO_PIN_3, //Timer2/3 - 3
SERVO_PIN_4, //Timer2/2 - 4 SERVO_PIN_4, //Timer2/2 - 4
SERVO_PIN_1, //Timer3/3 - 1 SERVO_PIN_1, //Timer3/3 - 1
#ifdef SERVO_PIN_5
SERVO_PIN_5, //Timer2/1 SERVO_PIN_5, //Timer2/1
#endif
#ifdef SERVO_PIN_6
SERVO_PIN_6, //Timer2/0 SERVO_PIN_6, //Timer2/0
#endif
// servo channels on input port // servo channels on input port
// 4, // PB14 CH1_IN - PPM1 Use this channels asd servo only if you use DSM via UART as RC SERVO_PIN_7, // PB15 CH2_IN - PPM2
5, // PB15 CH2_IN - PPM2 SERVO_PIN_8, // PC6 CH3_IN UART6
12, // PC6 CH3_IN UART6 SERVO_PIN_9, // PC7 CH4_IN UART6
13, // PC7 CH4_IN UART6 SERVO_PIN_10, // PC8 CH5_IN i2c
14, // PC8 CH5_IN i2c SERVO_PIN_11, // PC9 CH6_IN i2c
15, // PC9 CH6_IN i2c
}; };
// Arducopter, shifted 2 pins right to use up to 2 servos // Arducopter, shifted 2 pins right to use up to 2 servos
static const uint8_t output_channels_servo[]= { // pin assignment static const uint8_t output_channels_servo[]= { // pin assignment
SERVO_PIN_3, //Timer2/3 - 1 SERVO_PIN_3, //Timer2/3 - 1
SERVO_PIN_4, //Timer2/2 - 2 SERVO_PIN_4, //Timer2/2 - 2
#ifdef SERVO_PIN_5
SERVO_PIN_5, //Timer2/1 - 3 SERVO_PIN_5, //Timer2/1 - 3
#endif
#ifdef SERVO_PIN_6
SERVO_PIN_6, //Timer2/0 - 4 SERVO_PIN_6, //Timer2/0 - 4
#endif
SERVO_PIN_1, //Timer3/3 servo1 SERVO_PIN_1, //Timer3/3 servo1
SERVO_PIN_2, //Timer3/4 servo2 SERVO_PIN_2, //Timer3/4 servo2
// servo channels on input port // servo channels on input port
// 4, // PB14 CH1_IN - PPM1 Use this channels as servo only if you use DSM via UART as RC SERVO_PIN_7, // PB15 CH2_IN - PPM2
5, // PB15 CH2_IN - PPM2 SERVO_PIN_8, // PC6 CH3_IN UART6
12, // PC6 CH3_IN UART6 SERVO_PIN_9, // PC7 CH4_IN UART6
13, // PC7 CH4_IN UART6 SERVO_PIN_10, // PC8 CH5_IN i2c
14, // PC8 CH5_IN i2c SERVO_PIN_11, // PC9 CH6_IN i2c
15, // PC9 CH6_IN i2c
}; };
@ -176,29 +186,6 @@ void RCOutput::do_4way_if(AP_HAL::UARTDriver* uart) {
esc4wayProcess(uart); esc4wayProcess(uart);
} }
#ifdef DEBUG_INT
extern "C" int printf(const char *msg, ...);
static void isr_handler(){
uint32_t *sp;
#define FRAME_SHIFT 10 // uses IRQ handler itself
asm volatile ("mov %0, sp\n\t" : "=rm" (sp) );
// Stack frame contains:
// r0, r1, r2, r3, r12, r14, the return address and xPSR
// - Stacked R0 = sp[0]
// - Stacked R1 = sp[1]
// - Stacked R2 = sp[2]
// - Stacked R3 = sp[3]
// - Stacked R12 = sp[4]
// - Stacked LR = sp[5]
// - Stacked PC = sp[6]
// - Stacked xPSR= sp[7]
printf("pc=%lx lr=%lx\n", sp[FRAME_SHIFT+6], sp[FRAME_SHIFT+5]);
}
#endif
void RCOutput::lateInit(){ // 2nd stage with loaded parameters void RCOutput::lateInit(){ // 2nd stage with loaded parameters
@ -210,14 +197,6 @@ void RCOutput::lateInit(){ // 2nd stage with loaded parameters
output_channels = revo_motor_map[map]; output_channels = revo_motor_map[map];
InitPWM(); InitPWM();
#ifdef DEBUG_INT
uint8_t spin = output_channels[DEBUG_INT]; // motor 6 as button
GPIO::_pinMode(spin, INPUT_PULLUP);
Revo_handler h = { .vp = isr_handler };
GPIO::_attach_interrupt(spin, h.h, FALLING, 0);
#endif
} }
void RCOutput::InitPWM() void RCOutput::InitPWM()
@ -635,12 +614,6 @@ void RCOutput::enable_ch(uint8_t ch)
} }
fill_timers(); // re-calculate list of used timers fill_timers(); // re-calculate list of used timers
#ifdef DEBUG_INT
uint8_t spin = output_channels[DEBUG_INT]; // motor 6
GPIO::_pinMode(spin, INPUT_PULLUP);
#endif
} }
void RCOutput::disable_ch(uint8_t ch) void RCOutput::disable_ch(uint8_t ch)

View File

@ -151,18 +151,6 @@ extern const struct TIM_Channel PWM_Channels[] __FLASH__ = {
{ // 1 RC_IN2 { // 1 RC_IN2
.pin = PA2, // UART2 TX .pin = PA2, // UART2 TX
}, },
{ // 2 RC_IN3
.pin = (uint8_t)-1,
},
{ // 3 RC_IN4
.pin = (uint8_t)-1,
},
{ // 4 RC_IN5
.pin = (uint8_t)-1,
},
{ // 5 RC_IN6
.pin = (uint8_t)-1,
},
}; };

View File

@ -178,6 +178,13 @@
#define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_5 48 // PA1
#define SERVO_PIN_6 47 // PA0 #define SERVO_PIN_6 47 // PA0
// input pins as servo outputs
#define SERVO_PIN_7 5, // PB15 CH2_IN - PPM2
#define SERVO_PIN_8 12, // PC6 CH3_IN UART6
#define SERVO_PIN_9 13, // PC7 CH4_IN UART6
#define SERVO_PIN_10 14, // PC8 CH5_IN i2c
#define SERVO_PIN_11 15, // PC9 CH6_IN i2c
#define MOTOR_LAYOUT_DEFAULT 0 #define MOTOR_LAYOUT_DEFAULT 0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -184,6 +184,12 @@
#define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_5 48 // PA1
#define SERVO_PIN_6 47 // PA0 #define SERVO_PIN_6 47 // PA0
// input pins as servo outputs
#define SERVO_PIN_7 5, // PB15 CH2_IN - PPM2
#define SERVO_PIN_8 12, // PC6 CH3_IN UART6
#define SERVO_PIN_9 13, // PC7 CH4_IN UART6
#define SERVO_PIN_10 14, // PC8 CH5_IN i2c
#define SERVO_PIN_11 15, // PC9 CH6_IN i2c
#define MOTOR_LAYOUT_DEFAULT 0 #define MOTOR_LAYOUT_DEFAULT 0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -179,6 +179,13 @@
#define SERVO_PIN_5 48 // PA1 #define SERVO_PIN_5 48 // PA1
#define SERVO_PIN_6 47 // PA0 #define SERVO_PIN_6 47 // PA0
// input pins as servo outputs
#define SERVO_PIN_7 5, // PB15 CH2_IN - PPM2
#define SERVO_PIN_8 12, // PC6 CH3_IN UART6
#define SERVO_PIN_9 13, // PC7 CH4_IN UART6
#define SERVO_PIN_10 14, // PC8 CH5_IN i2c
#define SERVO_PIN_11 15, // PC9 CH6_IN i2c
#define MOTOR_LAYOUT_DEFAULT 0 #define MOTOR_LAYOUT_DEFAULT 0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -39,7 +39,7 @@ based on:
#include <syscalls.h> #include <syscalls.h>
#include <systick.h> #include <systick.h>
/* _end and _eccm is set in the linker command file */ /* _end and _eccm are set in the linker command file */
extern caddr_t _end; extern caddr_t _end;
extern caddr_t _eccm; extern caddr_t _eccm;
@ -63,7 +63,7 @@ int _getpid(void)
/* /*
* sbrk -- changes heap size size. Get nbytes more * sbrk -- changes heap size. Get nbytes more
* RAM. We just increment a pointer in what's * RAM. We just increment a pointer in what's
* left of memory on the board. * left of memory on the board.
*/ */
@ -108,8 +108,7 @@ static caddr_t _sbrk_ccm(int nbytes) {
if(stack_bottom) top = (uint32_t)stack_bottom; if(stack_bottom) top = (uint32_t)stack_bottom;
if ( top > (unsigned int)heap_ptr+nbytes) // there is place in stack, if stack in RAM it will be true too if ( top > (unsigned int)heap_ptr+nbytes) {// there is place in stack, if stack in RAM it will be true too
{
base = heap_ptr; base = heap_ptr;
heap_ptr += nbytes; heap_ptr += nbytes;
__brkval_ccm = heap_ptr; __brkval_ccm = heap_ptr;
@ -127,7 +126,6 @@ caddr_t sbrk_ccm(int nbytes) {
caddr_t _sbrk(int nbytes) { caddr_t _sbrk(int nbytes) {
return _sbrk_ram(nbytes); return _sbrk_ram(nbytes);
} }

View File

@ -135,7 +135,6 @@ extern void hal_go_next_task();
#define NVIC_CCR (*(volatile uint32_t *)0xE000ED14) #define NVIC_CCR (*(volatile uint32_t *)0xE000ED14)
// new common exception code // new common exception code
// TODO: we have task switching so if fault occures in task we can just remove task from queue
// //
void __attribute__((noreturn)) __error(uint32_t num, uint32_t pc, uint32_t lr, uint32_t flag) void __attribute__((noreturn)) __error(uint32_t num, uint32_t pc, uint32_t lr, uint32_t flag)
{ {
@ -191,32 +190,16 @@ void __attribute__((noreturn)) __error(uint32_t num, uint32_t pc, uint32_t lr, u
hal_stop_multitask(); hal_stop_multitask();
#if 0
#ifdef ERROR_USART
usart_putstr(ERROR_USART, "\r\n!!! Exception: ");
#ifdef DEBUG_BUILD
usart_putstr(ERROR_USART, faults[num]);
#else
usart_putudec(ERROR_USART, num);
#endif
usart_putstr(ERROR_USART, " at ");
usart_putudec(ERROR_USART, pc);
usart_putstr(ERROR_USART, " lr ");
usart_putudec(ERROR_USART, lr);
usart_putc(ERROR_USART, '\n');
usart_putc(ERROR_USART, '\r');
#endif
#else
#ifdef DEBUG_BUILD #ifdef DEBUG_BUILD
printf("\r\n!!! Exception: %s at %x LR=%x\n",faults[num], pc, lr); printf("\r\n!!! Exception: %s at %x LR=%x\n",faults[num], pc, lr);
#else #else
printf("\r\n!!! Exception: %d at %x LR=%x\n",num, pc, lr); printf("\r\n!!! Exception: %d at %x LR=%x\n",num, pc, lr);
#endif
#endif #endif
error_throb(num); error_throb(num);
} }
#if 0 #if 0 // not removed for case if something will require Timer5
uint32_t systick_micros(void) uint32_t systick_micros(void)
{ {
volatile uint32_t fms, lms; volatile uint32_t fms, lms;