- stm32 debugger tools
- Old school years
- Fixed Wing Landing
- sensor-selection
- multiple gcs
- GCS on android
stm32 debugger tools
- 20-10ping-adapter
- adapter-datasheet
- debugger-seller
- stlinkv2
or download
example blogs
This is a short writeup/tutorial on low-level debugging a Pixhawk with Ardupilot. It’s based on an issue discussed over at Build Library for Pixhawk 4 - serial outputs can’t be displayed 11, where one of the code examples (UART_test) would cause a system crash of the flight controller.
The tutorial should work with any STM32-based flight controller that has a JTAG port (i.e. Pixhawk).
- Hardware Setup
Required Hardware:
Flight controller with JTAG port ST-Link v2 7 with 10-pin adapter 4 The Flight controller may require a small plug 8 to solder on to the JTAG port.
Plug the flight controller and ST-Link to each other via the JTAG port (noting that the little notch on the JTAG connector points towards the SD card on the Pixhawk). Plug both devices’ USB cables to your computer.
hardwaresetup hardwaresetup.jpg 826×619 71.5 KB
- Software setup
A Linux system is recommended. Windows may be possible, but I’ve not tested that. ./ArduCopter.elf -h It is assumed that the arm-gcc compiler has already been installed. If not, see http://ardupilot.org/dev/docs/building-setup-linux.html 6
[OpenOCD](https://openocd.org0 1 is to be installed next via this command:
sudo apt-get install libusb-1.0-0-dev libusb-1.0-0 openocd
OpenOCD (with the ST-Link) is the bridge between GDB and the STM32 microcontroller on the Pixhawk.
- Debugging UART_test
For this example, I used the UART_test 4 example (as of 13/11/2019)github. This example produced the system crash described below. This code is in ./ardupilot/libraries/AP_HAL/examples/UART_test
Build and upload the debug variant of the UART_test example (noting that the –board may be different if you’re using a different board)
./waf configure --board=Pixhawk1-1M --debug --enable-asserts
./waf --target=examples/UART_test --upload
Before OpenOCD and GDB are run, their configuration files need to be copied to the build folder. Note that the build folder’s name is the same at the board’s name in the waf configuration above.
1 Go to the ./ardupilot/Tools/debug
folder
2 Copy openocd.cfg to ./ardupilot/build/Pixhawk1-1M/bin
3 Copy .gdbinit to ./ardupilot/build/Pixhawk1-1M/examples
4 Edit ~/.gdbinit to have the following text: set auto-load safe-path /
Next open up two terminals to run openOCD and GDB.
cd ./ardupilot/build/Pixhawk1-1M/bin
openocd
openocd
openocd.png
743×523 74.6 KB
cd ./ardupilot/build/Pixhawk1-1M/examples
arm-none-eabi-gdb ./UART_test
gdb
gdb.png
737×518 93.9 KB
The details of the system crash will be shown in GDB:
0x0800542e in HardFault_Handler ()
at ../../libraries/AP_HAL_ChibiOS/system.cpp:94
94 save_fault_watchdog(__LINE__, faultType, faultAddress);
Breakpoint 1 at 0x800549c: file ../../libraries/AP_HAL_ChibiOS/system.cpp, line 172.
Breakpoint 2 at 0x8005404: file ../../libraries/AP_HAL_ChibiOS/system.cpp, line 69.
Breakpoint 3 at 0x801d4cc: file ../../modules/ChibiOS/os/rt/src/chsys.c, line 19
Now, that’s just the watchdog handler. Let’s check the threads via the info threads command in GDB:
` 9 Thread 536952680 (Name: IOMCU, State: CURRENT) 0x080076fe in HardFault_Handler () at ../../libraries/AP_HAL_ChibiOS/system.cpp:94` So there is something in the IOMCU thread that is causing the error.
Use the i loc
command to view the code that, when executed, caused the crash:
lr_thd = 0x800bae9 <AP_Logger::WriteV(char const*, char const*, char const*, char const*, char const*, std::__va_list, bool)+28>,
pc = 0x800ba5c <AP_Logger::msg_fmt_for_name(char const*, char const*, char const*, char const*, char const*)+8>,
The IOMCU thread is trying to write to the logfile (AP_Logger) and encountering an error.
Looking back at the UART_test code, note that AP_Logger isn’t initialised anywhere. That’s why the system is crashing when trying to refer to a (non-existent) AP_Logger.
So, IOMCU assumes that there’s a valid AP_Logger. That’s fine for a full vehicle, but not the UART_test example.
We will edit IOMCU to check if there’s a valid logger first. Make the following changes to AP_IOMCU.cpp to check for AP_Logger befure trying to write:
if (now - last_log_ms >= 1000U) {
last_log_ms = now;
if (AP_Logger::get_singleton()) {
AP::logger().Write("IOMC", "TimeUS,Mem,TS,NPkt,Nerr,Nerr2,NDel", "QHIIIII",
AP_HAL::micros64(),
reg_status.freemem,
reg_status.timestamp_ms,
reg_status.total_pkts,
total_errors,
reg_status.num_errors,
num_delayed);
}
So we upload the changed firmware, debug again and see what happens…
Reading symbols from ./UART_test...done.
0x0800542e in HardFault_Handler ()
at ../../libraries/AP_HAL_Ch./ArduCopter.elf -hibiOS/system.cpp:94
94 save_fault_watchdog(__LINE__, faultType, faultAddress);
Breakpoint 1 at 0x800549c: file ../../libraries/AP_HAL_ChibiOS/system.cpp, line 172.
Breakpoint 2 at 0x8005404: file ../../libraries/AP_HAL_ChibiOS/system.cpp, line 69.
Breakpoint 3 at 0x801d4d8: file ../../modules/ChibiOS/os/rt/src/chsys.c, line 198.
(gdb) i loc
ctx = {
r0 = 0x0,
r1 = 0x802c928,
r2 = 0x802c8e4,
r3 = 0x0,
r12 = 0x0,
lr_thd = 0x8008b39 <AP_Logger::WriteV(char const*, char const*, char const*, char const*, char const*, std::__va_list, bool)+28>,
pc = 0x8008aac <AP_Logger::msg_fmt_for_name(char const*, char const*, char const*, char const*, char const*)+8>,
xpsr = 0x21000000,
s0 = 0x55555555,
s1 = 0x55555555,
s2 = 0x0,
s3 = 0x55555555,
s4 = 0x55555555,
s5 = 0x55555555,
s6 = 0x55555555,
s7 = 0x55555555,
s8 = 0x55555555,
s9 = 0x55555555,
s10 = 0x55555555,
s11 = 0x55555555,
s12 = 0x55555555,
s13 = 0x55555555,
s14 = 0x55555555,
s15 = 0x55555555,
fpscr = 0x55555555,
reserved = 0x55555555
}
faultAddress = <optimized out>
(gdb) info threads
[New Thread 536923896]
[New Thread 536939280]
[New Thread 536906352]
[New Thread 536912640]
[New Thread 536907424]
[New Thread 536905280]
[New Thread 536910032]
Id Target Id Frame
2 Thread 536923896 (Name: idle, State: READY) 0x080051a4 in _port_switch_from_isr ()
3 Thread 536939280 (Name: apm_uart, State: WTOREVT) chVTIsArmedI (
vtp=0x20010ac4) at ../../modules/ChibiOS/os/rt/include/chvt.h:243
4 Thread 536906352 (Name: apm_monitor, State: CURRENT) 0x0800542e in HardFault_Handler () at ../../libraries/AP_HAL_ChibiOS/system.cpp:94
5 Thread 536912640 (Name: apm_timer, State: SLEEPING) chVTIsArmedI (
vtp=0x2000a2c4 <_timer_thread_wa+2452>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
6 Thread 536907424 (Name: apm_rcin, State: SLEEPING) chVTIsArmedI (
vtp=0x20008e64 <_rcin_thread_wa+916>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
7 Thread 536905280 (Name: apm_io, State: SLEEPING) chVTIsArmedI (
vtp=0x200085fc <_io_thread_wa+2444>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
8 Thread 536910032 (Name: apm_storage, State: SLEEPING) chVTIsArmedI (
vtp=0x20009894 <_storage_thread_wa+2452>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
Another unchecked AP_Logger reference! This time in the apm_monitor thread.
We will make a similar edit to check if there’s a valid logger first. Make the following changes to ./libraries/AP_HAL_Chibios/Scheduler.cpp
:
if (AP_Logger::get_singleton()) {
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII",
AP_HAL::micros64(),
loop_delay,
pd.scheduler_task,
pd.internal_errors,
pd.internal_error_count,
pd.last_mavlink_msgid,
pd.last_mavlink_cmd,
pd.semaphore_line,
pd.spi_count,
pd.i2c_count);
} So we upload the changed firmware, debug again and see what happens…
Reading symbols from ./UART_test...done.
_idle_thread (p=0x0) at ../../modules/ChibiOS/os/rt/src/chsys.c:72
72 static void _idle_thread(void *p) {
Breakpoint 1 at 0x800549c: file ../../libraries/AP_HAL_ChibiOS/system.cpp, line 172.
Breakpoint 2 at 0x8005404: file ../../libraries/AP_HAL_ChibiOS/system.cpp, line 69.
Breakpoint 3 at 0x801d4e4: file ../../modules/ChibiOS/os/rt/src/chsys.c, line 198.
(gdb) i loc
No locals.
(gdb) info threads
[New Thread 536923896]
[New Thread 536939280]
[New Thread 536906352]
[New Thread 536912640]
[New Thread 536907424]
[New Thread 536905280]
[New Thread 536910032]
Id Target Id Frame
2 Thread 536923896 (Name: idle, State: CURRENT) _idle_thread (p=0x0)
at ../../modules/ChibiOS/os/rt/src/chsys.c:72
3 Thread 536939280 (Name: apm_uart, State: WTOREVT) chVTIsArmedI (
vtp=0x20010ac4) at ../../modules/ChibiOS/os/rt/include/chvt.h:243
4 Thread 536906352 (Name: apm_monitor, State: SLEEPING) chVTIsArmedI (
vtp=0x200089cc <_monitor_thread_wa+812>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
5 Thread 536912640 (Name: apm_timer, State: SLEEPING) chVTIsArmedI (
vtp=0x2000a2c4 <_timer_thread_wa+2452>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
6 Thread 536907424 (Name: apm_rcin, State: SLEEPING) chVTIsArmedI (
vtp=0x20008e64 <_rcin_thread_wa+916>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
7 Thread 536905280 (Name: apm_io, State: SLEEPING) chVTIsArmedI (
vtp=0x200085fc <_io_thread_wa+2444>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
8 Thread 536910032 (Name: apm_storage, State: SLEEPING) chVTIsArmedI (
vtp=0x20009894 <_storage_thread_wa+2452>)
at ../../modules/ChibiOS/os/rt/include/chvt.h:243
No crashes this time, so this UART_test should now run fine.
Finally, build and upload a non-debug version of UART_test:
./waf configure --board=Pixhawk1-1M
./waf --target=examples/UART_test --upload
And the expected output: output output.png 1168×399 43.9 KB
So, with the help of low-level debugging, UART_test is fixe
afroflight board
- pinouts on pcb
- MDK-ARM 과의 연결
ARM KEIL 에서
Flash 메뉴 - Configure flash tools 클릭
Debug 탭 클릭 - ST-Link Debugger 선택
Old school years
Fixed Wing Landing
PX4 enables autopilot-controlled fixed-wing (FW) landing in Missions, Land mode, and Return mode.
The landing logic has several phases, as shown below. In the first phase the vehicle will follow a fixed trajectory (FW_LND_ANG) towards the ground. At the flare landing altitude (FW_LND_FLALT) the vehicle will start to follow a flare path (the curve is based on the value of FW_LND_HVIRT).
The flare landing altitude is relative to the altitude that the FW vehicle “thinks” is ground level. In Land mode the ground altitude is not known and the vehicle will use assume it is at 0m (sea level). Often the ground level will be much higher than sea level, so the vehicle will land in the first phase (it will land on the ground before it reaches the flare altitude).
In a mission, Return mode, or if the vehicle has a range sensor fitted then ground level can be accurately estimated and landing behaviour will be as shown in the preceding diagram.
Landing is further affected by the following parameters:
Parameter | Description |
---|---|
FW_LND_ANG | Landing slope angle prior to flaring |
FW_LND_HVIRT | Virtual horizontal line/altitude used to calculate the flare trajectory. This represents the sub-ground altitude that the flare-path curve asymptotically approaches. |
FW_LND_FLALT | Landing flare altitude (relative to landing altitude) |
FW_LND_TLALT | Landing throttle limit altitude (relative landing altitude). The default value of -1.0 lets the system default to applying throttle limiting at 2/3 of the flare altitude. |
FW_LND_HHDIST | Landing heading hold horizontal distance |
FW_LND_USETER | Use terrain estimate (ground altitude from GPS) during landing. This is turned off by default and a waypoint or return altitude is normally used (or sea level for an arbitrary land position). |
FW_LND_FL_PMIN | Minimum pitch during flare. A positive sign means nose up Applied once FW_LND_TLALT is reached |
FW_LND_FL_PMAX | Maximum pitch during flare. A positive sign means nose up Applied once FW_LND_TLALT is reached |
FW_LND_AIRSPD_SC | Min. airspeed scaling factor for landing. Comment: Multiplying this factor with the minimum airspeed of the plane gives the target airspeed the landing approach. FW_AIRSPD_MIN x FW_LND_AIRSPD_SC |
sensor-selection
Sensors
PX4-based systems use sensors to determine vehicle state (needed for stabilization and to enable autonomous control). The vehicle states include: position/altitude, heading, speed, airspeed, orientation (attitude), rates of rotation in different directions, battery level, etc.
The system minimally requires a gyroscope, accelerometer, magnetometer (compass) and barometer. A GPS or other positioning system is needed to enable all automatic modes, and some assisted modes. Fixed wing and VTOL-vehicles should additionally include an airspeed sensor (very highly recommended).
The minimal set of sensors is incorporated into Pixhawk Series flight controllers (and may also be in other controller platforms). Additional/external sensors can be attached to the controller.
Below we describe some of the sensors. At the end there are links to information about sensor wiring.
GPS & Compass
PX4 supports a number of global navigation satellite system (GNSS) receivers and compasses (magnetometers). It also supports Real Time Kinematic (RTK) GPS Receivers, which extend GPS systems to centimetre-level precision.
:::note Pixhawk-series controllers include an internal compass. This may be useful on larger vehicles (e.g. VTOL) where it is possible to reduce electromagnetic interference by mounting the Pixhawk a long way from power supply lines. On small vehicles an external compass is almost always required. :::
We recommend the use of an external “combined” compass/GPS module mounted as far away from the motor/ESC power supply lines as possible - typically on a pedestal or wing (for fixed-wing).
Common GPS/compass hardware options are listed in: GPS/Compass.
multiple gcs
You can attach multiple additional ground control stations to SITL from MAVProxy. The simulated vehicle can then be controlled and viewed through any attached GCS.
First use the output command on the MAVProxy command prompt to determine where MAVProxy is sending packets:
GUIDED> output
GUIDED> 2 outputs
0: 127.0.0.1:14550
1: 127.0.0.1:14551
This tells us that we can connect Mission Planner to either UDP port 14550 or 14551, as shown on the dialog below.
Mission Planner: Connecting to a UDPPort
Tip
We could connect APM Planner 2 to the remaining port. If we needed a third port, we could add it as shown:
GUIDED> output add 127.0.0.1:14553
Mission Planner can then be used to control the simulated vehicle in exactly the same way as though it were a real vehicle. We can reproduce the previous “takeoff-circle-land” example as shown below
- Change to Guided mode, arm the throttle, and the takeoff
- Open the Flight Data screen and select the Actions tab on the bottom left. This is where we cna change the bmode and st commands.
- Select Gudied in the mode selection list and then press the set Mode button
- Select the Arm/Disarm button
- Right click on the ma and select Takeoff. Then enter the desired takeoff altitude
Takeoff must start within 15 seconds of arming, or the motors will disarm.
Change to CIRCLE mode on the Action tab and watch the copter circle on the map.
You can change the circle radius in the CONFIG/TUNING screen. Select Full Parameters List, then the Find button and search for CIRCLE_MODE. When you’ve changed the value press the Write Params button to save them to the vehicle.
When you’re ready to land you can set the mode to RTL.
Running SITL with a GCS without MAVProxy
It is also possible to interact with SITL without using MAVProxy at all using ArduCopter.elf (in the ArduCopter directory).
Run the file in the Cygwin Terminal, specifying a home position and vehicle model as shown below
hamis_000@XPS12ultra ~/ardupilot/ArduCopter
$ ./ArduCopter.elf --home -35,149,584,270 --model quad
Started model quad at -35,149,584,270 at speed 1.0
Starting sketch 'ArduCopter'
Starting SITL input
bind port 5760 for 0
Serial port 0 on TCP port 5760
Waiting for connection ....
The command output shows that you can connect to SITL using TCP/IP at port 5760.
In Mission Planner we first change the link type to TCP and then press the Connect button. Click through the remote host and remote Port prompts as these default to the correct values.
Mission Planner: Connecting toSITL using TCP
Mission Planner will then connect and can be used just as before.
Tip
ArduCopter.elf has other startup options, which you can use using the -h command line parameter:
./ArduCopter.elf -h
GCS on android
The following wiki, pages and posts are tagged with
Title | Type | Excerpt |
---|---|---|
gcs and cloud | post | Mon, Jan 31, 22, sample4 from sass2 product sample4 |
overview and initial powerup | post | Mon, Jan 31, 22, sample1.md of sass2 product2_sample files The most advanced hardware and software ecosystem for enterprise drones |
smartAP | post | Mon, Jan 31, 22, sample5 from sass2 product2 sample5 |
smartAPLink and faq | post | Mon, Jan 31, 22, sample3 from sass2 product2 sample3 |
telemetry and advanced software | post | Mon, Jan 31, 22, sample2.md of sass2 product2 sample2 file |
px4 docker image for jvsim simulation | post | 목, 2월 10, 22, docker image implmentation for docker px4 simuation |
qtcreator wiki from drone guide dev-setup | post | 화, 2월 15, 22, planning phase research for dashboard elements using |
offboard control using pixhawk raspi mavros | post | Wed, Feb 16, 22, hitl setup and configuraiton using pixhawk raspi mavros and px4 |
setup gazebo for simulation | post | Wed, Feb 16, 22, pixhawk ros gazebo gcs simulation |
setup mavros and px4 | post | Wed, Feb 16, 22, setup mavros and px4 |
testing sitl drone | post | Wed, Feb 16, 22, process to launch sitl drone |
ros and px4 architecture and data flow | post | Wed, Feb 16, 22, examine how data flows for user interface and drone control |
setup ros indigo with tutlesim | post | Wed, Feb 16, 22, pixhawk gcs simulation series 2 with ros indigo |
connecting raspi to matek f406 wing | post | Fri, Feb 18, 22, hardware setup with raspi 4 with matek f406 wing |
px4 simulation for gazebo | post | Fri, Feb 18, 22, simulation instruciton from px4 |
Let's roll and conquer! | post | Monday, Third week with jdlab and first week probably for actual work |
brainstorming session prior to setting out on gcs development | post | Mon, Feb 21, 22, pool resources and ideas into one single gcs you can develop |
overview of epp and eps for airframes | post | Tue, Feb 22, 22, research before business call to manufactueres |
connecting rpi to gcs with the use of uavmatrix on uavcast pro | post | Mon, Feb 28, 22, supported raspi board pinout maps and setup guide |
creating custom mission points for fixed wings | post | Fri, Mar 18, 22, p-turn or turnaround insertion to the mission raw data for exit and entry for p-turnaround and side/front-lap coverage creation that willmod... |
gStreamer vs qtAv | post | Wed, Mar 30, 22, qt movie qmovie phonon video player |
realtime georeferencing plus imu overlay | post | Tue, Apr 05, 22, how to add vehicle status sensor data to georeferencing |
rtk reach m2 receiver documentation | post | Wed, Apr 06, 22, rtk reach receiver wifi 5g lte |
avionics on airfoil and frames | post | Thu, Apr 07, 22, airfoil materials, designs and innovations in the avionics |
using openTX on radiomaster TX16s | post | Sun, Apr 10, 22, rc reciever transmitter opentx radiomaster configuration simulation |
adding GPS and IMU data to photos post flight | post | Mon, Apr 11, 22, perform post processing of gps/imu data or develop camera firmware lib to infuse IMU from fc to exif metadata |
BMU BMC BMS battery management | post | Thu, Apr 14, 22, to check the usage and health of batteries at all phases of flight cycle |
viewpro custom pwm | post | Thu, Apr 14, 22, customize viewpro camera and gimball with mavlink |
raspberrypi video streaming | post | Fri, Apr 22, 22, configure and setup raspi to enable streaming on mavlink and to advance to LTE transmission |
lx network, airlink, gcs and data transmission on smart radio, rf mesh and quantum encryption | post | Tue, Apr 26, 22, all about setup and how it operates and managed |