mirror of https://github.com/ArduPilot/ardupilot
SITL: mark logger Write() calls as streaming where appropriate
This commit is contained in:
parent
11afdb1ef2
commit
477f936560
|
@ -348,7 +348,7 @@ void AirSim::recv_fdm(const sitl_input& input)
|
|||
// @Field: GX: Simulated gyroscope, X-axis
|
||||
// @Field: GY: Simulated gyroscope, Y-axis
|
||||
// @Field: GZ: Simulated gyroscope, Z-axis
|
||||
AP::logger().Write("ASM1", "TimeUS,TUS,R,P,Y,GX,GY,GZ",
|
||||
AP::logger().WriteStreaming("ASM1", "TimeUS,TUS,R,P,Y,GX,GY,GZ",
|
||||
"QQffffff",
|
||||
AP_HAL::micros64(),
|
||||
state.timestamp,
|
||||
|
@ -375,7 +375,7 @@ void AirSim::recv_fdm(const sitl_input& input)
|
|||
// @Field: PZ: simulation's position, Z-axis
|
||||
// @Field: Alt: simulation's gps altitude
|
||||
// @Field: SD: simulation's earth-frame speed-down
|
||||
AP::logger().Write("ASM2", "TimeUS,AX,AY,AZ,VX,VY,VZ,PX,PY,PZ,Alt,SD",
|
||||
AP::logger().WriteStreaming("ASM2", "TimeUS,AX,AY,AZ,VX,VY,VZ,PX,PY,PZ,Alt,SD",
|
||||
"Qfffffffffff",
|
||||
AP_HAL::micros64(),
|
||||
accel_body.x,
|
||||
|
|
|
@ -165,7 +165,7 @@ void Aircraft::update_position(void)
|
|||
// @Field: PN: Position - North component
|
||||
// @Field: PE: Position - East component
|
||||
// @Field: PD: Position - Down component
|
||||
AP::logger().Write("SITL", "TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD", "Qfffffffff",
|
||||
AP::logger().WriteStreaming("SITL", "TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD", "Qfffffffff",
|
||||
AP_HAL::micros64(),
|
||||
velocity_ef.x, velocity_ef.y, velocity_ef.z,
|
||||
accel_ef.x, accel_ef.y, accel_ef.z,
|
||||
|
@ -811,7 +811,7 @@ void Aircraft::smooth_sensors(void)
|
|||
// @Field: R2: DCM Roll
|
||||
// @Field: P2: DCM Pitch
|
||||
// @Field: Y2: DCM Yaw
|
||||
AP::logger().Write("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2",
|
||||
AP::logger().WriteStreaming("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2",
|
||||
"Qffffffffffff",
|
||||
AP_HAL::micros64(),
|
||||
degrees(angle_differential.x),
|
||||
|
|
|
@ -378,7 +378,7 @@ void JSON::recv_fdm(const struct sitl_input &input)
|
|||
// @Field: GX: Simulated gyroscope, X-axis (rad/sec)
|
||||
// @Field: GY: Simulated gyroscope, Y-axis (rad/sec)
|
||||
// @Field: GZ: Simulated gyroscope, Z-axis (rad/sec)
|
||||
AP::logger().Write("JSN1", "TimeUS,TStamp,R,P,Y,GX,GY,GZ",
|
||||
AP::logger().WriteStreaming("JSN1", "TimeUS,TStamp,R,P,Y,GX,GY,GZ",
|
||||
"ssrrrEEE",
|
||||
"F???????",
|
||||
"Qfffffff",
|
||||
|
@ -405,7 +405,7 @@ void JSON::recv_fdm(const struct sitl_input &input)
|
|||
// @Field: AN: simulation's acceleration, North (m/s^2)
|
||||
// @Field: AE: simulation's acceleration, East (m/s^2)
|
||||
// @Field: AD: simulation's acceleration, Down (m/s^2)
|
||||
AP::logger().Write("JSN2", "TimeUS,VN,VE,VD,AX,AY,AZ,AN,AE,AD",
|
||||
AP::logger().WriteStreaming("JSN2", "TimeUS,VN,VE,VD,AX,AY,AZ,AN,AE,AD",
|
||||
"snnnoooooo",
|
||||
"F?????????",
|
||||
"Qfffffffff",
|
||||
|
|
|
@ -104,7 +104,7 @@ void JSON_Master::receive(struct sitl_input &input)
|
|||
// @Field: frame_rate: Slave instance's desired frame rate
|
||||
// @Field: frame_count: Slave instance's current frame count
|
||||
// @Field: active: 1 if the servo outputs are being used from this instance
|
||||
AP::logger().Write("SLV1", "TimeUS,Instance,magic,frame_rate,frame_count,active",
|
||||
AP::logger().WriteStreaming("SLV1", "TimeUS,Instance,magic,frame_rate,frame_count,active",
|
||||
"s#----",
|
||||
"F?????",
|
||||
"QBHHIB",
|
||||
|
@ -134,7 +134,7 @@ void JSON_Master::receive(struct sitl_input &input)
|
|||
// @Field: C13: channel 13 output
|
||||
// @Field: C14: channel 14 output
|
||||
// @Field: C15: channel 15 output
|
||||
AP::logger().Write("SLV2", "TimeUS,Instance,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14,C15",
|
||||
AP::logger().WriteStreaming("SLV2", "TimeUS,Instance,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14,C15",
|
||||
"s#YYYYYYYYYYYYYY",
|
||||
"F?--------------",
|
||||
"QBHHHHHHHHHHHHHH",
|
||||
|
|
Loading…
Reference in New Issue