Browse Source

SITL: log airspeed in SIM2

gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
7643c5d3f3
  1. 8
      libraries/SITL/SIM_Aircraft.cpp

8
libraries/SITL/SIM_Aircraft.cpp

@ -475,13 +475,15 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm)
// @Field: VN: Velocity north // @Field: VN: Velocity north
// @Field: VE: Velocity east // @Field: VE: Velocity east
// @Field: VD: Velocity down // @Field: VD: Velocity down
// @Field: As: Airspeed
Vector3d pos = get_position_relhome(); Vector3d pos = get_position_relhome();
Vector3f vel = get_velocity_ef(); Vector3f vel = get_velocity_ef();
AP::logger().WriteStreaming("SIM2", "TimeUS,PN,PE,PD,VN,VE,VD", AP::logger().WriteStreaming("SIM2", "TimeUS,PN,PE,PD,VN,VE,VD,As",
"Qdddfff", "Qdddffff",
AP_HAL::micros64(), AP_HAL::micros64(),
pos.x, pos.y, pos.z, pos.x, pos.y, pos.z,
vel.x, vel.y, vel.z); vel.x, vel.y, vel.z,
airspeed_pitot);
} }
} }

Loading…
Cancel
Save