New Simulator Sensor Timeout issue

Hi,

I’m working on integrating a new simulator platform (Silent Wings) but I’m running into a issue with the sensor update. Silent Wings send a state update at a rate of between 30 to 50 hz.

As a test, I’ve increased the timeout value in the sensor voting as such:

	if (_hil_enabled) { // HIL has less accurate timing so increase the timeouts a bit
	_baro.voter.set_timeout(5000000);
	_mag.voter.set_timeout(5000000);
	_gyro.voter.set_timeout(5000000);
	_accel.voter.set_timeout(5000000);
}

But I keep getting these error:

WARN [ecl/EKF] 189211910143: EKF baro hgt timeout - reset to baro
ERROR [sensors] Accel #0 fail: TIMEOUT!
ERROR [sensors] Sensor Accel #0 failed. Reconfiguring sensor priorities.

I’ve already disable lockstep.

Thanks

@AlexandreBorowczyk Looks ike you need to set the sensor_id?

@Jaeyoung-Lim I’m using the same simulator code as with the gazebo sitl simulation. I haven’t changed the accelerator sensor declaration:

@AlexandreBorowczyk Could you check if the sensor topics actually being sent in that case?

Would be awesome if we can support Silent wings from px4 for autonomous soaring applications.
Would this be something accessible? I would definitely be interested

It is publishing and the timing looks ok. I will get a log and take a closer look.

Actually this is exactly what we are developing!
Check us out at: https://www.notostechnologies.com/

@AlexandreBorowczyk Looks awesome! Do you have any plans to contribute the silent wings bridge to px4? Flight gear is being added to px4 (link), but for soaring it would be cool if silent wings would be available too.

I was also interested in this topic and in my project mav_soaring was trying to simulate soaring / thermals in gazebo. However, this would only be very simple models and simulators like flight gear will help a lot.

There is also a pull request for supporting soaring setpoints for the firmware, if you are interestd.

Very nice! Always fun to meet another soaring enthusiast!
Thanks for sharing the Flight Gear bridge, I will design the SilentWings one on a similar basis.

On the short term, we are planning on contributing our Glide mode to the PX4.

As for my issue, I will take a closer look at would Flight Gear does it but I’ve put a small piece of code to display the delay between to “updates” of the Accel driver. And here is the results:

INFO [drivers_accelerometer] Sensor_accel delay 16688
INFO [drivers_accelerometer] Sensor_accel delay 16610
INFO [drivers_accelerometer] Sensor_accel delay 16750
INFO [drivers_accelerometer] Sensor_accel delay 16645
ERROR [sensors] Accel #0 fail: TIMEOUT!
ERROR [sensors] Sensor Accel #0 failed. Reconfiguring sensor priorities.
WARN [sensors] Remaining sensors after failover event 0: Accel #0 priority: 1
INFO [drivers_accelerometer] Sensor_accel delay 23223
INFO [drivers_accelerometer] Sensor_accel delay 10141
INFO [drivers_accelerometer] Sensor_accel delay 16666
INFO [drivers_accelerometer] Sensor_accel delay 16646

Seems like the error could be associate to slightly longer delay but a 23223 usec delay shouldn’t be issue…

@AlexandreBorowczyk Actually your errors might be coming from silent wings not being able to work with Lockstep. Flightgear bridge works without lockstep. Maybe try disabling lockstep with silent wings. This might fix your problem

Lockstep has already been disabled and by the timestamp on the sensor_accel the update rate is 60 to 50 Hz which should be ok, no?

I curious to better understand the architecture behind the sensor Timeout. Do you know about it?

Hi, is there some update on that topic? :slight_smile:
Regarding the timeout issues. You should see that we implemented an upsampling and noise injection to the sensor data in the PX4-FlightGear-bridge. The noise avoids of PX4 to evaluate the sensor data as stalled.

I am interested in this, because thermal gliding simulation will be a nice feature for our autogyro stress testing.