mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: Gazebo index out of bound
- imu_orientation_quat[size=3] is fed to Quaternion[size=4] which causes an index-out-of-range problem
This commit is contained in:
parent
59dda49cce
commit
9737c426eb
@ -54,7 +54,7 @@ private:
|
||||
double timestamp;
|
||||
double imu_angular_velocity_rpy[3];
|
||||
double imu_linear_acceleration_xyz[3];
|
||||
double imu_orientation_quat[3];
|
||||
double imu_orientation_quat[4];
|
||||
double velocity_xyz[3];
|
||||
double position_xyz[3];
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user