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

[Bug] Simulated gyro sensor data gets inverted at fast rates #23469

Open
Jaeyoung-Lim opened this issue Jul 30, 2024 · 3 comments
Open

[Bug] Simulated gyro sensor data gets inverted at fast rates #23469

Jaeyoung-Lim opened this issue Jul 30, 2024 · 3 comments

Comments

@Jaeyoung-Lim
Copy link
Member

Jaeyoung-Lim commented Jul 30, 2024

Describe the bug

I am trying to simulate a fast rotating vehicle, but the gyro data seems to get inverted at high rotating rates (~50rad/s).

I have checked the data up to the FIFO of the gyrodriver, and the data seems correct. However what comes out of the driver is not correct.

// gyro 0 is simulated FIFO
static constexpr float GYRO_FIFO_SCALE = math::radians(2000.f / 32768.f);
static constexpr float GYRO_FIFO_RANGE = math::radians(2000.f);
_px4_gyro[sensors.id].set_scale(GYRO_FIFO_SCALE);
_px4_gyro[sensors.id].set_range(GYRO_FIFO_RANGE);
if (_gyro_stuck[sensors.id]) {
_px4_gyro[sensors.id].updateFIFO(_last_gyro_fifo);
} else if (!_gyro_blocked[sensors.id]) {
_px4_gyro[sensors.id].set_temperature(_sensors_temperature);
_last_gyro_fifo.samples = 1;
_last_gyro_fifo.dt = time - _last_gyro_fifo.timestamp_sample;
_last_gyro_fifo.timestamp_sample = time;
_last_gyro_fifo.x[0] = sensors.xgyro / GYRO_FIFO_SCALE;
_last_gyro_fifo.y[0] = sensors.ygyro / GYRO_FIFO_SCALE;
_last_gyro_fifo.z[0] = sensors.zgyro / GYRO_FIFO_SCALE;
_px4_gyro[sensors.id].updateFIFO(_last_gyro_fifo);
}

To Reproduce

Use this branch: https://github.com/PX4/PX4-Autopilot/tree/pr-monocopter

make px4_sitl gazebo-classic_monocopter
  • Switch to manual mode and increase the throttle
    349954900-a4437eaf-4b76-4d7c-a0ac-eae7eb8b9580

Expected behavior

In case the gyro saturates, it should report clipping rather than report some other random value

Screenshot / Media

image

Flight Log

https://review.px4.io/plot_app?log=faa25343-059d-4a67-96ca-101816085007

Software Version

https://github.com/PX4/PX4-Autopilot/tree/pr-monocopter

Flight controller

SITL

Vehicle type

None

How are the different components wired up (including port information)

No response

Additional context

No response

@DronecodeBot
Copy link

This issue has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-sync-q-a-july-31-2024/39922/2

@DronecodeBot
Copy link

This issue has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-sync-q-a-july-31-2024/39922/1

@farhangnaderi
Copy link
Contributor

When landing a FW I also experienced this rotation. Not sure if related though!

@github-actions github-actions bot added the stale label Aug 30, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

3 participants