HAL_F4Light: fixed parameter's numbers for some boards

This commit is contained in:
night-ghost 2018-03-09 12:49:36 +05:00 committed by Lucas De Marchi
parent c4e8aeb105
commit 7fad79ca81
7 changed files with 35 additions and 31 deletions

View File

@ -1,4 +1,5 @@
#include <AP_HAL_F4Light/hardware/hal/syscalls.h>
#include <AP_HAL_F4Light/params.h>
#define HAL_NEEDS_PARAM_HELPER

View File

@ -194,8 +194,8 @@
*/
#define BOARD_HAL_VARINFO \
AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \
AP_GROUPINFO("SD_REFORMAT", 17, AP_Param_Helper, _sd_format, 0),
AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), \
AP_GROUPINFO("SD_REFORMAT", 31, AP_Param_Helper, _sd_format, 0),
// parameters

View File

@ -1,10 +1,10 @@
this is for Revolution/RevoMini board with removed 25q16 and soldered 25q128 or 25q256. This is very easy!
I tried to maintain compatibility with the OpenPilot documentation. The main difference - FlexiPort can
be Serial and external I2C port is on pins 7&8 of Input port. But this can be changed by HAL_FLEXI_I2C parameter
be Serial and external I2C port is on pins 7&8 of Input port. But this can be changed by BRD_FLEXI_I2C parameter
Main Port - telemetry, Serial1. As a variant it can be used as SBUS input with hardware inverter (Parameter HAL_UART_SBUS)
Main Port - telemetry, Serial1. As a variant it can be used as SBUS input with hardware inverter (Parameter BRD_UART_SBUS)
FlexiPort - OSD, Serial2
Uart6 (pins 5&6) - GPS
@ -19,7 +19,7 @@ pins 7&8 of Input port are SCL and SDA of external I2C (or Tx and Rx for SoftSer
Output Port for MOTORs
Connect to PWM output pins in ArduCopter, CleanFlight or OpenPilot order, and set parameter HAL_MOTOR_LAYOUT accordingly
Connect to PWM output pins in ArduCopter, CleanFlight or OpenPilot order, and set parameter BRD_MOTOR_LAYOUT accordingly
5&6 PWM Output pins are Rx and Tx of Serial4 - but only for quads (except motor layout 1, see below) or planes

View File

@ -209,7 +209,7 @@
*/
#define BOARD_HAL_VARINFO \
AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), \
AP_GROUPINFO("FLEXI_I2C", 30, AP_Param_Helper, _flexi_i2c, 0),
AP_GROUPINFO("FLEXI_I2C", 31, AP_Param_Helper, _flexi_i2c, 0),
// parameters
#define BOARD_HAL_PARAMS \

View File

@ -5,5 +5,5 @@
# bare metal binary
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/f4light_Revolution.bin
dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduPlane/f4light_Revolution.bin -R
dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduPlane/f4light_Revolution_EE128_bl.bin

View File

@ -208,8 +208,8 @@
#define BOARD_HAL_VARINFO \
AP_GROUPINFO("FLEXI_I2C", 30, AP_Param_Helper, _flexi_i2c, 0), \
AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), \
AP_GROUPINFO("SD_REFORMAT", 31, AP_Param_Helper, _sd_format, 0),
AP_GROUPINFO("USB_STORAGE", 31, AP_Param_Helper, _usb_storage, 0), \
AP_GROUPINFO("SD_REFORMAT", 32, AP_Param_Helper, _sd_format, 0),
// parameters

View File

@ -94,29 +94,32 @@ void __attribute__((noreturn)) error_throb(uint32_t num){
/* Error fade. */
while (1) {
uint16_t k;
for(k=0; k<num; k++) {
if (CC == TOP_CNT) {
slope = -1;
} else if (CC == 0) {
slope = 1;
for(k=0; k<num+1; k++) {
uint32_t m;
for(m=100000;m>0;m--){
if (CC == TOP_CNT) {
slope = -1;
} else if (CC == 0) {
slope = 1;
}
if (i == TOP_CNT) {
CC += slope;
i = 0;
}
if (i < CC) {
n=1;
} else {
n=0;
}
gpio_write_bit(pp->gpio_device, pp->gpio_bit, n);
volatile int j =10;
while(--j);
i++;
}
if (i == TOP_CNT) {
CC += slope;
i = 0;
}
if (i < CC) {
n=1;
} else {
n=0;
}
gpio_write_bit(pp->gpio_device, pp->gpio_bit, n);
volatile int j =10;
while(--j);
i++;
}
emerg_delay(3000); // on 168MHz ~0.1ms so 300ms
}