mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-30 00:24:08 +08:00
Fix build breakage on mavlink update
This commit is contained in:
parent
54a5f7a138
commit
2f715b74dd
@ -391,11 +391,9 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
|
||||
|
||||
f.timestamp = hrt_absolute_time();
|
||||
f.flow_timestamp = flow.time_usec;
|
||||
f.flow_raw_x = flow.flow_x;
|
||||
f.flow_raw_y = flow.flow_y;
|
||||
f.flow_comp_x_m = flow.flow_comp_m_x;
|
||||
f.flow_comp_y_m = flow.flow_comp_m_y;
|
||||
f.ground_distance_m = flow.ground_distance;
|
||||
f.flow_raw_x = flow.integrated_x;
|
||||
f.flow_raw_y = flow.integrated_y;
|
||||
f.ground_distance_m = flow.distance;
|
||||
f.quality = flow.quality;
|
||||
f.sensor_id = flow.sensor_id;
|
||||
|
||||
@ -413,7 +411,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
|
||||
r.timestamp = hrt_absolute_time();
|
||||
r.error_count = 0;
|
||||
r.type = RANGE_FINDER_TYPE_LASER;
|
||||
r.distance = flow.ground_distance;
|
||||
r.distance = flow.distance;
|
||||
r.minimum_distance = 0.0f;
|
||||
r.maximum_distance = 40.0f; // this is set to match the typical range of real sensors, could be made configurable
|
||||
r.valid = (r.distance > r.minimum_distance) && (r.distance < r.maximum_distance);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user