mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_HAL_F4light: fixed compilation for boards AirbotF4, AirbotV2 and CL_Racing_F4. Corrected prefix for binaries
This commit is contained in:
parent
094e284737
commit
e2b628c471
1
.gitignore
vendored
1
.gitignore
vendored
@ -94,3 +94,4 @@ test.ArduCopter/*
|
|||||||
GPATH
|
GPATH
|
||||||
GRTAGS
|
GRTAGS
|
||||||
GTAGS
|
GTAGS
|
||||||
|
config.mk
|
||||||
|
@ -160,28 +160,6 @@
|
|||||||
* a lot of minor enhancements
|
* a lot of minor enhancements
|
||||||
|
|
||||||
|
|
||||||
Warning!!!
|
|
||||||
EEPROM emulation in Flash cause periodic program hunging on time of sector erase! So to allow auto-save parameters
|
|
||||||
like MOT_THST_HOVER - MOT_HOVER_LEARN to be 2 you should defer parameter writing (Param HAL_EE_DEFER)
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
Timer usage:
|
|
||||||
|
|
||||||
1 RC-Output on some boards
|
|
||||||
2 RC-Output
|
|
||||||
3 RC-Output
|
|
||||||
4 soft_i2c0, PPM_IN on AirbotV2
|
|
||||||
5 micros()
|
|
||||||
6 event generation for WFE
|
|
||||||
7 scheduler
|
|
||||||
8 PPM_IN
|
|
||||||
9 soft_i2c1
|
|
||||||
10 soft_i2c2
|
|
||||||
11
|
|
||||||
12 PPM_IN
|
|
||||||
13 driver's io_completion
|
|
||||||
14 schedule tail timer
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,3 +1,27 @@
|
|||||||
this is universal HAL for almost any F4 board, without any external OS
|
this is universal HAL for almost any F4 board, without any external OS
|
||||||
|
|
||||||
per-board Readme files are in boards/{board}/1_Readme.md
|
per-board Readme files are in boards/{board}/1_Readme.md
|
||||||
|
|
||||||
|
|
||||||
|
Warning!!!
|
||||||
|
EEPROM emulation in Flash cause periodic program hunging on time of sector erase! So to allow auto-save parameters
|
||||||
|
like MOT_THST_HOVER - MOT_HOVER_LEARN to be 2 you should defer parameter writing (Param BRD_EE_DEFER)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
Timer usage:
|
||||||
|
|
||||||
|
1 RC-Output on some boards
|
||||||
|
2 RC-Output
|
||||||
|
3 RC-Output
|
||||||
|
4 soft_i2c0, PPM_IN on AirbotV2
|
||||||
|
5 micros()
|
||||||
|
6 event generation for WFE
|
||||||
|
7 scheduler
|
||||||
|
8 PPM_IN
|
||||||
|
9 soft_i2c1
|
||||||
|
10 soft_i2c2
|
||||||
|
11
|
||||||
|
12 PPM_IN
|
||||||
|
13 driver's io_completion
|
||||||
|
14 schedule tail timer
|
||||||
|
@ -1 +0,0 @@
|
|||||||
boards/revomini_Revolution/1_read_ME.md
|
|
@ -654,15 +654,16 @@ uint16_t EEPROMClass::read(uint16_t Address, uint16_t *Data)
|
|||||||
|
|
||||||
Address &= ADDRESS_MASK;
|
Address &= ADDRESS_MASK;
|
||||||
|
|
||||||
|
uint32_t ptr = pageEnd;
|
||||||
|
|
||||||
// Check each active page address starting from end - the last value written
|
// Check each active page address starting from end - the last value written
|
||||||
for (pageBase += 6; pageEnd >= pageBase; pageEnd -= 4){
|
for (pageBase += 6; ptr >= pageBase; ptr -= 4){
|
||||||
if (read_16(pageEnd) == Address){// Compare the read address with the virtual address
|
if (read_16(ptr) == Address){// Compare the read address with the virtual address
|
||||||
*Data = read_16(pageEnd - 2); // Get content of Address-2 which is variable value
|
*Data = read_16(ptr - 2); // Get content of Address-2 which is variable value
|
||||||
return EEPROM_OK;
|
return EEPROM_OK;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return ReadStatus value: (0: variable exist, 1: variable doesn't exist)
|
|
||||||
return EEPROM_BAD_ADDRESS;
|
return EEPROM_BAD_ADDRESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -15,8 +15,6 @@
|
|||||||
#include "HAL_F4Light_Class.h"
|
#include "HAL_F4Light_Class.h"
|
||||||
#include "RCInput.h"
|
#include "RCInput.h"
|
||||||
#include "Util.h"
|
#include "Util.h"
|
||||||
//#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
|
||||||
//#include <AP_HAL_Empty/AP_HAL_Empty_Private.h>
|
|
||||||
|
|
||||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||||
|
|
||||||
@ -27,11 +25,6 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_WAYBACK_ENABLE
|
|
||||||
#include "AP_WayBack/AP_WayBack.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#if defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)
|
#if defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)
|
||||||
#include "sd/SD.h"
|
#include "sd/SD.h"
|
||||||
@ -280,10 +273,10 @@ void HAL_F4Light::run(int argc,char* const argv[], Callbacks* callbacks) const
|
|||||||
|
|
||||||
|
|
||||||
#if defined(BOARD_SDCARD_NAME) && defined(BOARD_SDCARD_CS_PIN)
|
#if defined(BOARD_SDCARD_NAME) && defined(BOARD_SDCARD_CS_PIN)
|
||||||
printf("\nEnabling SD at %ldms\n", millis());
|
printf("\nEnabling SD at %ldms\n", AP_HAL::millis());
|
||||||
SD.begin(F4Light::SPIDeviceManager::_get_device(BOARD_SDCARD_NAME));
|
SD.begin(F4Light::SPIDeviceManager::_get_device(BOARD_SDCARD_NAME));
|
||||||
#elif defined(BOARD_DATAFLASH_FATFS)
|
#elif defined(BOARD_DATAFLASH_FATFS)
|
||||||
printf("\nEnabling DataFlash as SD at %ldms\n", millis());
|
printf("\nEnabling DataFlash as SD at %ldms\n", AP_HAL::millis());
|
||||||
SD.begin(F4Light::SPIDeviceManager::_get_device(HAL_DATAFLASH_NAME));
|
SD.begin(F4Light::SPIDeviceManager::_get_device(HAL_DATAFLASH_NAME));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -321,33 +314,6 @@ void HAL_F4Light::run(int argc,char* const argv[], Callbacks* callbacks) const
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#if USE_WAYBACK == ENABLED && defined(WAYBACK_DEBUG)
|
|
||||||
|
|
||||||
#define SERIAL_BUFSIZE 128
|
|
||||||
|
|
||||||
static AP_HAL::UARTDriver* uart;
|
|
||||||
|
|
||||||
static void getSerialLine(char *cp ){ // получение строки
|
|
||||||
uint8_t cnt=0; // строка не длиннее 256 байт
|
|
||||||
|
|
||||||
while(true){
|
|
||||||
if(!uart->available()){
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
char c=uart->read();
|
|
||||||
|
|
||||||
if(c==0x0d || (cnt && c==0x0a)){
|
|
||||||
cp[cnt]=0;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
if(c==0x0a) continue; // skip unneeded LF
|
|
||||||
|
|
||||||
cp[cnt]=c;
|
|
||||||
if(cnt<SERIAL_BUFSIZE) cnt++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static bool lateInitDone=false;
|
static bool lateInitDone=false;
|
||||||
|
|
||||||
@ -454,117 +420,6 @@ void HAL_F4Light::lateInit() {
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if USE_WAYBACK == ENABLED && defined(WAYBACK_DEBUG)
|
|
||||||
{
|
|
||||||
uint8_t dbg = hal_param_helper->_dbg_wayback;
|
|
||||||
if(dbg){
|
|
||||||
|
|
||||||
dbg -=1;
|
|
||||||
|
|
||||||
if(dbg < sizeof(uarts)/sizeof(AP_HAL::UARTDriver**) ){
|
|
||||||
AP_HAL::UARTDriver** up = uarts[dbg];
|
|
||||||
if(up && *up){
|
|
||||||
uart = *up;
|
|
||||||
|
|
||||||
AP_WayBack track;
|
|
||||||
Scheduler::_delay(5000); // time to connect
|
|
||||||
|
|
||||||
track.set_debug_mode(true);
|
|
||||||
track.init();
|
|
||||||
track.start();
|
|
||||||
|
|
||||||
uart->begin(115200);
|
|
||||||
|
|
||||||
uart->println("send pairs 'lat,lon'");
|
|
||||||
uart->println("send H for help");
|
|
||||||
|
|
||||||
char buffer[SERIAL_BUFSIZE];
|
|
||||||
float x,y;
|
|
||||||
char *bp=buffer;
|
|
||||||
uint16_t i=0;
|
|
||||||
|
|
||||||
while(1){
|
|
||||||
getSerialLine(buffer);
|
|
||||||
|
|
||||||
if(buffer[1]==0) {
|
|
||||||
switch(buffer[0]){
|
|
||||||
case 'G': // return by track
|
|
||||||
// get point
|
|
||||||
|
|
||||||
track.stop();
|
|
||||||
|
|
||||||
while(track.get_point(x,y)){
|
|
||||||
uart->print(x);
|
|
||||||
uart->print(",");
|
|
||||||
uart->println(y);
|
|
||||||
}
|
|
||||||
uart->println(".");
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 'c':
|
|
||||||
case 'C':
|
|
||||||
hal_param_helper->_dbg_wayback = 0;
|
|
||||||
hal_param_helper->_dbg_wayback.save();
|
|
||||||
goto done;
|
|
||||||
|
|
||||||
|
|
||||||
case 'R': // Reset
|
|
||||||
track.stop();
|
|
||||||
track.end();
|
|
||||||
track.init();
|
|
||||||
track.start();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 'S': // show current state
|
|
||||||
i=0;
|
|
||||||
while(true){
|
|
||||||
uint16_t k=i;
|
|
||||||
if(!track.show_track(i, x, y )) break;
|
|
||||||
uart->print(k);
|
|
||||||
uart->print(",");
|
|
||||||
uart->print(x);
|
|
||||||
uart->print(",");
|
|
||||||
uart->println(y);
|
|
||||||
}
|
|
||||||
uart->println(".");
|
|
||||||
break;
|
|
||||||
case 'h':
|
|
||||||
case 'H':
|
|
||||||
uart->println("send pairs 'lat,lon'");
|
|
||||||
uart->println("send G to get point");
|
|
||||||
|
|
||||||
uart->println("send S to show track point");
|
|
||||||
uart->println("send R to reset track");
|
|
||||||
uart->println("send C to cancel this mode");
|
|
||||||
break;
|
|
||||||
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
// given a point - "x,y"
|
|
||||||
bp=buffer;
|
|
||||||
|
|
||||||
while(*bp) {
|
|
||||||
if(*bp++ == ',') break;
|
|
||||||
}
|
|
||||||
x=atof(buffer);
|
|
||||||
y=atof(bp);
|
|
||||||
|
|
||||||
uint32_t t=AP_HAL::micros();
|
|
||||||
|
|
||||||
track.add_point(x,y);
|
|
||||||
t=AP_HAL::micros() - t;
|
|
||||||
|
|
||||||
uart->print("# time=");
|
|
||||||
uart->println(t);
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
done:
|
|
||||||
#endif
|
|
||||||
|
|
||||||
RCOutput::lateInit(); // 2nd stage - now with loaded parameters
|
RCOutput::lateInit(); // 2nd stage - now with loaded parameters
|
||||||
|
|
||||||
|
27
libraries/AP_HAL_F4Light/boards/f4light_Airbot/support/Rebuild.sh
Executable file
27
libraries/AP_HAL_F4Light/boards/f4light_Airbot/support/Rebuild.sh
Executable file
@ -0,0 +1,27 @@
|
|||||||
|
#git submodule init && git submodule update
|
||||||
|
export TOOLCHAIN
|
||||||
|
|
||||||
|
ROOT=`cd ../../../../..; pwd`
|
||||||
|
|
||||||
|
export PATH=/usr/local/bin:$PATH
|
||||||
|
|
||||||
|
echo $ROOT
|
||||||
|
|
||||||
|
|
||||||
|
( # AirBotF4 board
|
||||||
|
cd $ROOT/ArduPlane
|
||||||
|
make f4light-clean
|
||||||
|
make f4light BOARD=f4light_Airbot &&
|
||||||
|
cp $ROOT/ArduPlane/f4light_Airbot.bin $ROOT/Release/Plane &&
|
||||||
|
cp $ROOT/ArduPlane/f4light_Airbot.hex $ROOT/Release/Plane &&
|
||||||
|
cp $ROOT/ArduPlane/f4light_Airbot.dfu $ROOT/Release/Plane
|
||||||
|
) && (
|
||||||
|
cd $ROOT/ArduCopter
|
||||||
|
make f4light-clean
|
||||||
|
make f4light BOARD=f4light_Airbot &&
|
||||||
|
|
||||||
|
cp $ROOT/ArduCopter/f4light_Airbot.bin $ROOT/Release/Copter &&
|
||||||
|
cp $ROOT/ArduCopter/f4light_Airbot.hex $ROOT/Release/Copter &&
|
||||||
|
cp $ROOT/ArduCopter/f4light_Airbot.dfu $ROOT/Release/Copter
|
||||||
|
)
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
#production binary for bootloader
|
#production binary for bootloader
|
||||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_Revolution.bin
|
||||||
|
|
||||||
# bare metal binary
|
# bare metal binary
|
||||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/revomini_Airbot.bin
|
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/f4light_Airbot.bin
|
||||||
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/revomini_Airbot.bin
|
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/f4light_Airbot.bin
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
# production binary with bootloader
|
# production binary with bootloader
|
||||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
#bare metal binary
|
#bare metal binary
|
||||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/revo_cl_racing.bin 0x08000000 && /usr/local/stlink/st-util -m
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_Airbot.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
# production binary with bootloader
|
# production binary with bootloader
|
||||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
#bare metal binary
|
#bare metal binary
|
||||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/revo_cl_racing.bin 0x08000000 && /usr/local/stlink/st-util -m
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/f4light_Airbot.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -34,3 +34,11 @@ How to get voltage/current reading(tested on omnibus, should work on other targe
|
|||||||
- BAT_AMP_PERVOLT 38.0 (or 17 for apm power module)
|
- BAT_AMP_PERVOLT 38.0 (or 17 for apm power module)
|
||||||
|
|
||||||
Don't try to configure Curr/Vol reading from Initial setup page of MP, because VOL/CURR variables will be reset.
|
Don't try to configure Curr/Vol reading from Initial setup page of MP, because VOL/CURR variables will be reset.
|
||||||
|
|
||||||
|
Attention!
|
||||||
|
|
||||||
|
If you select PPM (both via jumper or removing 0 ohm resistor) UART1 is no more used for RC IN and can be
|
||||||
|
used for telemetry (Serial1 on MP settings).
|
||||||
|
|
||||||
|
Once PPM is selected you can use this pin for RC IN with PPM/SBUS/DSM, the parser in the HAL is able to understand
|
||||||
|
which protocol are you using and to decode it properly.
|
@ -1,7 +1,7 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
# production binary with bootloader
|
# production binary with bootloader
|
||||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
#bare metal binary
|
#bare metal binary
|
||||||
/usr/local/stlink/st-flash --reset read readout.bin 0x08000000 0x100000
|
/usr/local/stlink/st-flash --reset read readout.bin 0x08000000 0x100000
|
@ -11,11 +11,11 @@ echo $ROOT
|
|||||||
( # AirBotF4 board
|
( # AirBotF4 board
|
||||||
cd $ROOT/ArduCopter
|
cd $ROOT/ArduCopter
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light VERBOSE=1 BOARD=revomini_AirbotV2
|
make f4light VERBOSE=1 BOARD=f4light_AirbotV2
|
||||||
) && (
|
) && (
|
||||||
cd $ROOT/ArduPlane
|
cd $ROOT/ArduPlane
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light VERBOSE=1 BOARD=revomini_AirbotV2
|
make f4light VERBOSE=1 BOARD=f4light_AirbotV2
|
||||||
)
|
)
|
||||||
|
|
||||||
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
@ -1,12 +1,12 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
#production binary for bootloader
|
#production binary for bootloader
|
||||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_AirbotV2.bin
|
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_AirbotV2.bin
|
||||||
|
|
||||||
# bare metal binary
|
# bare metal binary
|
||||||
|
|
||||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#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 ../../../../../ArduCopter/revomini_Revolution.bin -R
|
#dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduCopter/f4light_Revolution.bin -R
|
||||||
|
|
||||||
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/revo_cl_racing.bin -R
|
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/f4light_AirbotV2.bin -R
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
# production binary with bootloader
|
# production binary with bootloader
|
||||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
#bare metal binary
|
#bare metal binary
|
||||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/MiniF4_OSD.bin 0x08000000 && /usr/local/stlink/st-util -m
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
# production binary with bootloader
|
# production binary with bootloader
|
||||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
#bare metal binary
|
#bare metal binary
|
||||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/revomini_Airbot.bin 0x08000000 && /usr/local/stlink/st-util -m
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/f4light_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -11,11 +11,11 @@ echo $ROOT
|
|||||||
( # AirBotF4 board
|
( # AirBotF4 board
|
||||||
cd $ROOT/ArduCopter
|
cd $ROOT/ArduCopter
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light VERBOSE=1 BOARD=revomini_AirbotV2
|
make f4light VERBOSE=1 BOARD=f4light_AirbotV2
|
||||||
) && (
|
) && (
|
||||||
cd $ROOT/ArduPlane
|
cd $ROOT/ArduPlane
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light VERBOSE=1 BOARD=revomini_AirbotV2
|
make f4light VERBOSE=1 BOARD=f4light_AirbotV2
|
||||||
)
|
)
|
||||||
|
|
||||||
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
@ -1,12 +1,12 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
#production binary for bootloader
|
#production binary for bootloader
|
||||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_AirbotV2.bin
|
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_AirbotV2.bin
|
||||||
|
|
||||||
# bare metal binary
|
# bare metal binary
|
||||||
|
|
||||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#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 ../../../../../ArduCopter/revomini_Revolution.bin -R
|
#dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduCopter/f4light_Revolution.bin -R
|
||||||
|
|
||||||
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/revomini_AirbotV2.bin -R
|
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/f4light_AirbotV2.bin -R
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
# production binary with bootloader
|
# production binary with bootloader
|
||||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
#bare metal binary
|
#bare metal binary
|
||||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/revomini_Airbot.bin 0x08000000 && /usr/local/stlink/st-util -m
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
# production binary with bootloader
|
# production binary with bootloader
|
||||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
#bare metal binary
|
#bare metal binary
|
||||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/revomini_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/f4light_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -1,8 +1,8 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
#production binary for bootloader
|
#production binary for bootloader
|
||||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_AirbotV2.bin
|
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_AirbotV2.bin
|
||||||
|
|
||||||
# bare metal binary
|
# bare metal binary
|
||||||
dfu-util -a 0 --dfuse-address 0x08000000 -D ../../../../../ArduCopter/MiniF4_OSD.bin
|
dfu-util -a 0 --dfuse-address 0x08000000 -D ../../../../../ArduCopter/f4light_MiniF4_OSD.bin
|
||||||
|
|
@ -0,0 +1,9 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
|
||||||
|
# production binary with bootloader
|
||||||
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
|
#bare metal binary
|
||||||
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_MiniF4_OSD.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -11,11 +11,11 @@ echo $ROOT
|
|||||||
( # AirBotF4 board
|
( # AirBotF4 board
|
||||||
cd $ROOT/ArduCopter
|
cd $ROOT/ArduCopter
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light VERBOSE=1
|
make f4light
|
||||||
) && (
|
) && (
|
||||||
cd $ROOT/ArduPlane
|
cd $ROOT/ArduPlane
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light VERBOSE=1
|
make f4light
|
||||||
)
|
)
|
||||||
|
|
||||||
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
#production binary for bootloader
|
#production binary for bootloader
|
||||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_Revolution.bin
|
||||||
|
|
||||||
# bare metal binary
|
# bare metal binary
|
||||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#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/revomini_Revolution.bin -R
|
dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduPlane/f4light_Revolution.bin -R
|
||||||
|
|
@ -1,9 +1,9 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
#production binary for bootloader
|
#production binary for bootloader
|
||||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_Revolution.bin
|
||||||
|
|
||||||
# bare metal binary
|
# bare metal binary
|
||||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#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 ../../../../../ArduCopter/revomini_Revolution.bin -R
|
dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduCopter/f4light_Revolution.bin -R
|
||||||
|
|
@ -0,0 +1,9 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
|
||||||
|
# production binary with bootloader
|
||||||
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
|
#bare metal binary
|
||||||
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_Revolution.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -0,0 +1,9 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
|
||||||
|
# production binary with bootloader
|
||||||
|
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/f4light_Revolution.bin 0x08010000
|
||||||
|
|
||||||
|
#bare metal binary
|
||||||
|
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/f4light_Revolution.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||||
|
|
||||||
|
|
@ -11,10 +11,10 @@ echo $ROOT
|
|||||||
( # AirBotF4 board
|
( # AirBotF4 board
|
||||||
cd $ROOT/ArduCopter
|
cd $ROOT/ArduCopter
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light BOARD=revo_cl_racing
|
make f4light BOARD=f4light_cl_racing
|
||||||
) && (
|
) && (
|
||||||
cd $ROOT/ArduPlane
|
cd $ROOT/ArduPlane
|
||||||
make f4light-clean
|
make f4light-clean
|
||||||
make f4light BOARD=revo_cl_racing
|
make f4light BOARD=f4light_cl_racing
|
||||||
)
|
)
|
||||||
|
|
@ -1,12 +1,12 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
|
|
||||||
#production binary for bootloader
|
#production binary for bootloader
|
||||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_AirbotV2.bin
|
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/f4light_AirbotV2.bin
|
||||||
|
|
||||||
# bare metal binary
|
# bare metal binary
|
||||||
|
|
||||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
#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 ../../../../../ArduCopter/revomini_Revolution.bin -R
|
#dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduCopter/f4light_Revolution.bin -R
|
||||||
|
|
||||||
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/revomini_AirbotV2.bin -R
|
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/f4light_cl_racing.bin -R
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user