Skip to content

Conversation

magicrub
Copy link
Contributor

@magicrub magicrub commented Jun 3, 2025

If you start a sim without setting param SIM_SPEEDUP then it will default to -1. That can't be good. Luckily, what's actually used in the SITL code is target_speedup that can be fetched via get_speedup() within the Airplane class and that set_speedup() at boot does a sanity check on the param. However, AP_Logger looks directly at the param value and sets a timeout depending on that.

When it's negative it hangs the logio thread.

This PR does two things:
change SIM_SPEEDUP default from -1 to +1
sanity check sitl->speedup in logger. It's the only place in the code that uses it

@magicrub magicrub added the BUG label Jun 3, 2025
@timtuxworth
Copy link
Contributor

Thanks Tom - I've found that using the default on Mac crashes SITL. I always set --speedup 1 on the command line as a workaround, I guess it might be related to this.

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great find! That MacOSX thing has been a pain since forever.

OTOH, I don't know why a really long timeout_ms here would necessarily kill MacOSX in the way that it does...

@@ -1057,7 +1057,7 @@ bool AP_Logger_File::io_thread_alive() const
// disk. Unfortunately these hardware devices do not obey our
// SITL speedup options, so we allow for it here.
SITL::SIM *sitl = AP::sitl();
if (sitl != nullptr) {
if (sitl != nullptr && sitl->speedup > 0) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't we be using get_speedup() here?

Tim pointed out that he uses speedup on the command-line; if he does that then the number used here would be incorrect?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, using get_speedup() would be better but I didn't see any easy way for AP_Logger to reach down into a SIM::AIRCRAFT class.

@@ -228,7 +228,7 @@ const AP_Param::GroupInfo SIM::var_info[] = {
// @Description: Runs the simulation at multiples of normal speed. Do not use if realtime physics, like RealFlight, is being used
// @Range: 1 10
// @User: Advanced
AP_GROUPINFO("SPEEDUP", 52, SIM, speedup, -1),
AP_GROUPINFO("SPEEDUP", 52, SIM, speedup, 1),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This -1 is used elsewhere in the code as a flag value, eg.

    if (!is_equal(last_speedup, float(sitl->speedup)) && sitl->speedup > 0) {

maybe better to just use the method in the logger library and leave this thing sleep...

Suggested change
AP_GROUPINFO("SPEEDUP", 52, SIM, speedup, 1),
AP_GROUPINFO("SPEEDUP", 52, SIM, speedup, -1),

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yeah.. I dunno. I saw that code there, it's literally the only other place looking at the param. Seems convoluted for a run-once scheme. I think using a negative number is just bad practice here. For example, this -1 value would only here here on the first run after a --wipe but not the second run.. so what is it accomplishing?

Comment on lines +1060 to 1061
if (sitl != nullptr && sitl->speedup > 0) {
timeout_ms *= sitl->speedup;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (sitl != nullptr && sitl->speedup > 0) {
timeout_ms *= sitl->speedup;
if (sitl != nullptr) {
timeout_ms *= sitl->get_speedup();

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

doesn't compile.

@peterbarker
Copy link
Contributor

OK, correct fix is probably to move all the time handling code (sync_frame_time) out of SIM_Aircraft.

We should probably merge this this-century, however.

@timtuxworth are you able to test this PR?

@magicrub
Copy link
Contributor Author

magicrub commented Jun 6, 2025

I talked to @peterbarker about this and we both agree the better solution is to go through get_speedup() which I tried to use but we can't reqch that from our normal libraries so it requires larger infrastructure changes that start to become out of scope so this is good as-is for now until we get those larger infrastructure changes at a later time. Just waiting on a test confirmation from @timtuxworth to merge.

@timtuxworth
Copy link
Contributor

Might take me a couple of days, I'm on the road, but I'll test it as soon as I get back to Edmonton likely Monday/Tuesday.

@timtuxworth
Copy link
Contributor

This works. Tested in SITL on Mac M1 Pro. Without this fix SITL will crash unless you pass --speedup 1 on the command line (which sim_vehicle.py does by default, which is a workaround to this problem).

Now running a SITL instance of ardupilot on a Mac doesn't crash.

Copy link
Contributor

@timtuxworth timtuxworth left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Tested on a Mac (Apple Silicone), SITL will now run without crashing if there is no --speedup parameter passed.

@peterbarker
Copy link
Contributor

Merged, thanks!

@magicrub
Copy link
Contributor Author

@timtuxworth Thanks for testing!

@peterbarker peterbarker merged commit f7c0bf6 into ArduPilot:master Jun 17, 2025
103 of 104 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants