Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix px4 connection for wsl 2. #3603

Merged
merged 44 commits into from
May 6, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
44 commits
Select commit Hold shift + click to select a range
dd27458
fix px4 connection for wsl 2.
lovettchris Apr 16, 2021
b30ee91
enable throttling to 250 hz and fix bug in lockstep, should not send …
lovettchris Apr 16, 2021
1f3368b
add mavlink 2 support
lovettchris Apr 16, 2021
1c15604
make test terminate when it finds a problem, so you can capture the r…
lovettchris Apr 16, 2021
006d4e2
Merge settings improvements from PR 3546
lovettchris Apr 16, 2021
3b82fef
fix build and update docs.
lovettchris Apr 16, 2021
30ab123
fix unreal build
lovettchris Apr 16, 2021
b0b5de3
compute checksum on telemetry messages.
lovettchris Apr 17, 2021
71ff206
fix compiler warning.
lovettchris Apr 17, 2021
24d1bb6
Move telemetry to separate thread to get it out of the update() loop.…
lovettchris Apr 18, 2021
62048e5
guard telemetry variables with a mutex.
lovettchris Apr 18, 2021
938046f
make actuator delay an average
lovettchris Apr 18, 2021
9608bb4
add missing script files
lovettchris Apr 18, 2021
cb46217
fix pwsh support
lovettchris Apr 18, 2021
cfc7eec
add update_time to mavlinktelemetry
lovettchris Apr 18, 2021
642539a
Merge branch 'master' into clovett/mavlinkfixes
lovettchris Apr 19, 2021
f943770
add requirements.txt for pythonclient.
lovettchris Apr 20, 2021
92f3f3f
add info on how to use mavlink logs and px4 log viewer to debug a bad…
lovettchris Apr 20, 2021
bf71a53
Merge branch 'clovett/mavlinkfixes' of github.com:microsoft/AirSim in…
lovettchris Apr 20, 2021
db62395
Merge branch 'master' into clovett/mavlinkfixes
lovettchris Apr 20, 2021
cbdff5b
fix install link
lovettchris Apr 20, 2021
d48f5c0
add link to logging.
lovettchris Apr 20, 2021
65c3b4b
Merge branch 'master' into clovett/mavlinkfixes
lovettchris Apr 24, 2021
f7d2fea
fix drone server wsl2 connection.
lovettchris Apr 24, 2021
ad5534a
CR feedback.
lovettchris Apr 27, 2021
3d8f8b2
fix ros wrapper compile.
lovettchris Apr 27, 2021
e894d3a
script to test flying up high
lovettchris Apr 28, 2021
9d2012e
merge master
lovettchris Apr 28, 2021
0b81265
fix missing stopLoggingReceiveMessage
lovettchris Apr 28, 2021
f72de5f
nasty merge with master
lovettchris Apr 28, 2021
62b08da
consistency with logviewer logging and add docs.
lovettchris Apr 28, 2021
6db1f21
Pause physics update loop while waiting for actuator controls during …
lovettchris Apr 28, 2021
6fdb9b7
add missing update
lovettchris Apr 28, 2021
d28ace6
cleanup unnecessary cmake messages.
lovettchris Apr 28, 2021
f28f32b
Fix code formatting
lovettchris Apr 29, 2021
b717da4
fix typos.
lovettchris Apr 29, 2021
609031b
fix typo in udpate_rate
lovettchris Apr 29, 2021
def8bc0
fix bugs.
lovettchris Apr 30, 2021
c04924f
clang format
lovettchris Apr 30, 2021
6c747c7
cr fixes
lovettchris Apr 30, 2021
ade1289
Merge branch 'master' into clovett/mavlinkfixes
lovettchris May 3, 2021
e434f41
Add info on lockstep and steppable clock.
lovettchris May 3, 2021
ef5a6a6
add lockstep to toc
lovettchris May 4, 2021
6db5c7f
Make sure each buffer is zero'd out before reading bytes. Remove unn…
lovettchris May 5, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
add info on how to use mavlink logs and px4 log viewer to debug a bad…
… flight.
  • Loading branch information
lovettchris committed Apr 20, 2021
commit 92f3f3f67f5bfcedc936a93f43128789d553d7c0
9 changes: 6 additions & 3 deletions PythonClient/multirotor/stability_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,11 @@ def is_unstable(self, amount):
print("{}: min={}, max={}, mean={}, stddev={}".format(self.name, minimum, maximum, mean, stddev))
return (maximum - minimum) > amount

print("### TEST STARTED ###")
print("This test takes 20 minutes.")

iteration = 0
while True:
while iteration < 10:
iteration += 1
x = Numbers("x")
y = Numbers("y")
Expand All @@ -55,7 +58,7 @@ def is_unstable(self, amount):

# fly for 2 minutes
start = time.time()
while time.time() < start + 300:
while time.time() < start + 120:
state = client.getMultirotorState()
x_val = state.kinematics_estimated.position.x_val
y_val = state.kinematics_estimated.position.y_val
Expand Down Expand Up @@ -84,4 +87,4 @@ def is_unstable(self, amount):

time.sleep(5)

print("### Test Passed ###")
Binary file added docs/images/px4_debugging.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/images/px4_nice.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
2 changes: 1 addition & 1 deletion docs/log_viewer.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ estimation catches up with reality, this is more visible after a bad crash.

### Installation

If you can't build the LogViewer.sln, there is also a [click once installer](http://www.lovettsoftware.com/LovettSoftware/Downloads/Px4LogViewer/Px4LogViewer.application).
If you can't build the LogViewer.sln, there is also a [click once installer](http://www.lovettsoftware.com/Downloads/Px4LogViewer/Px4LogViewer.application).

### Configuration

Expand Down
52 changes: 39 additions & 13 deletions docs/px4_logging.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,19 +21,6 @@ AirSim can capture mavlink log files if you add the following to the PX4 section

AirSim will create a timestamped log file in this folder for each "armed/disarmed" flight session.

You can also create log files using the `MavLinkTest` app to the Simulator and enable logging
of all mavlink commands to and from the PX4.
```
MavLinkTest -server:127.0.0.1:14550 -logdir:d:\temp
```

Sometimes you will also want to log the "output" from the Simulator that is being sent to the PX4.
Specifically this will capture the "hilgps" and "hilsensor" messages that are generated by the
Simulator. To do that run this as well:
```
MavLinkTest -server:127.0.0.1:14389 -logdir:d:\temp\output
```

You will then see log files organized by date in d:\temp\logs, specifically *input.mavlink and *output.mavlink files.

## MavLink LogViewer
Expand All @@ -50,3 +37,42 @@ INFO [logger] Opened log file: rootfs/fs/microsd/log/2017-03-27/20_02_49.ulg

If you are using Pixhawk hardware in HIL mode, then set parameter `SYS_LOGGER=1`
using QGroundControl. PX4 will write log file on device which you can download at later date using QGroundControl.

## Debugging a bad flight

You can use these *.mavlink log files to debug a bad flight using the [LogViewer](log_viewer.md).
For example, AirSim/PX4 flight may misbehave if you run it on an under powered computer.
The following shows what might happen in that situation.

![screenshot](images/px4_debugging.png)

In this flight we ran a simple `commander takeoff` test as performed
by `PythonClient/multirotor/stability_test.py` and the flight started off fine, but then went crazy at the end and the drone crashed. So why is that? What can the log file show?

Here we've plotted the following 5 metrics:
- `hil_gps.alt` - the simulated altitude sent from AirSim to PX4
- `telemetry.update_rate` - the rate AirSim is performing the critical drone update loop in updates per second.
- `telemetry.update_time` - the average time taken inside AirSim performing the critical drone update loop.
- `telemetry.actuation_delay` - this is a very interesting metric measuring how long it takes PX4 to send back updated actuator controls message (motor power)
- `actuator_controls.0` - the actuator controls signal from PX4 for the first rotor.

What we see then with these metrics is that things started off nicely, with nice flat altitude, high update rate in the 275 to 300 fps range, and a nice low update time inside AirSim around 113 microseconds, and a nice low actuation delay in the round trip from PX4. The actuator controls also stabilize quickly to a nice flat line.

But then the update_time starts to climb, at the same time the actuation_delay climbs and we see a little tip in actuator_controls.
This dip should not happen, the PX4 is panicking over loss of update rate but it recovers.

But then we see actuator controls go crazy, a huge spike in actuation delay, and around this time we see a message from AirSim saying `lockstep disabled`. A delay over 100 millisecond triggers AirSim into jumping out of lockstep mode and the PX4 goes nuts and the drone crashes.

The button line is that if a simple `takeoff` cannot maintain steady smooth flight and you see these kinds of spikes and uneven update rates
then it means you are running AirSim on a computer that does not have enough horsepower.

This is what a simple takeoff and hover and land should look like:

![nice](images/px4_nice.png)

Here you see the `update_rate` sticking the target of 333 updates per second.
You also see the `update_time` a nice flat 39 microseconds and the `actuator_delay`
somewhere between 1.1 and 1.7 milliseconds, and the resulting `actuator_controls`
a lovely flat line.