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

AP_HAL_SITL: improve periph simulation efficiency #27541

Merged
merged 1 commit into from
Jul 16, 2024
Merged
Changes from all commits
Commits
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
5 changes: 2 additions & 3 deletions libraries/AP_HAL_SITL/SITL_Periph_State.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,10 +124,9 @@ void SITL_State::wait_clock(uint64_t wait_time_usec)
{
while (AP_HAL::micros64() < wait_time_usec) {
struct sitl_input input {};
sitl_model->update(input);
sitl_model->update(input); // delays up to 1 millisecond
sim_update();
update_voltage_current(input, 0);
usleep(100);
}
}

Expand Down Expand Up @@ -195,7 +194,7 @@ void SimMCast::multicast_read(void)
printf("Waiting for multicast state\n");
}
struct SITL::sitl_fdm state;
while (sock.recv((void*)&state, sizeof(state), 0) != sizeof(state)) {
while (sock.recv((void*)&state, sizeof(state), 1) != sizeof(state)) {
// nop
}
if (_sitl->state.timestamp_us == 0) {
Expand Down
Loading