mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: mark logger Write() calls as streaming where appropriate
This commit is contained in:
parent
477f936560
commit
1b21077edd
@ -215,7 +215,7 @@ void ModeFlowHold::flowhold_flow_to_angle(Vector2f &bf_angles, bool stick_input)
|
|||||||
// @Field: Iy: Integral part of PI controller, Y-Axis
|
// @Field: Iy: Integral part of PI controller, Y-Axis
|
||||||
|
|
||||||
if (log_counter++ % 20 == 0) {
|
if (log_counter++ % 20 == 0) {
|
||||||
AP::logger().Write("FHLD", "TimeUS,SFx,SFy,Ax,Ay,Qual,Ix,Iy", "Qfffffff",
|
AP::logger().WriteStreaming("FHLD", "TimeUS,SFx,SFy,Ax,Ay,Qual,Ix,Iy", "Qfffffff",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
(double)sensor_flow.x, (double)sensor_flow.y,
|
(double)sensor_flow.x, (double)sensor_flow.y,
|
||||||
(double)bf_angles.x, (double)bf_angles.y,
|
(double)bf_angles.x, (double)bf_angles.y,
|
||||||
@ -491,7 +491,7 @@ void ModeFlowHold::update_height_estimate(void)
|
|||||||
// @Field: LastInsH: Last used INS height in optical flow sensor height estimation calculations
|
// @Field: LastInsH: Last used INS height in optical flow sensor height estimation calculations
|
||||||
// @Field: DTms: Time between optical flow sensor updates. This should be less than 500ms for performing the height estimation calculations
|
// @Field: DTms: Time between optical flow sensor updates. This should be less than 500ms for performing the height estimation calculations
|
||||||
|
|
||||||
AP::logger().Write("FHXY", "TimeUS,DFx,DFy,DVx,DVy,Hest,DH,Hofs,InsH,LastInsH,DTms", "QfffffffffI",
|
AP::logger().WriteStreaming("FHXY", "TimeUS,DFx,DFy,DVx,DVy,Hest,DH,Hofs,InsH,LastInsH,DTms", "QfffffffffI",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
(double)delta_flowrate.x,
|
(double)delta_flowrate.x,
|
||||||
(double)delta_flowrate.y,
|
(double)delta_flowrate.y,
|
||||||
|
@ -227,7 +227,7 @@ void ModeThrow::run()
|
|||||||
// @Field: HgtOk: True if the vehicle is within 50cm of the demanded height
|
// @Field: HgtOk: True if the vehicle is within 50cm of the demanded height
|
||||||
// @Field: PosOk: True if the vehicle is within 50cm of the demanded horizontal position
|
// @Field: PosOk: True if the vehicle is within 50cm of the demanded horizontal position
|
||||||
|
|
||||||
AP::logger().Write(
|
AP::logger().WriteStreaming(
|
||||||
"THRO",
|
"THRO",
|
||||||
"TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk",
|
"TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk",
|
||||||
"s-nnoo----",
|
"s-nnoo----",
|
||||||
|
@ -1002,7 +1002,7 @@ void ToyMode::thrust_limiting(float *thrust, uint8_t num_motors)
|
|||||||
// @Field: M4: Motor 4 pwm output
|
// @Field: M4: Motor 4 pwm output
|
||||||
|
|
||||||
if (motor_log_counter++ % 10 == 0) {
|
if (motor_log_counter++ % 10 == 0) {
|
||||||
AP::logger().Write("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH",
|
AP::logger().WriteStreaming("THST", "TimeUS,Vol,Mul,M1,M2,M3,M4", "QffHHHH",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
(double)filtered_voltage,
|
(double)filtered_voltage,
|
||||||
(double)thrust_mul,
|
(double)thrust_mul,
|
||||||
|
Loading…
Reference in New Issue
Block a user