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:
Tom Pittenger 2015-07-20 17:26:37 -07:00 committed by Andrew Tridgell
parent 59dda49cce
commit 9737c426eb

View File

@ -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];
};