mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Remove obstacle avoidance MAVLink Heartbeat check
This commit is contained in:
parent
04cd247c90
commit
0b370ab5d3
@ -51,13 +51,11 @@ bool heartbeat_type_open_drone_id # MAV_TYPE_ODID
|
||||
bool heartbeat_component_telemetry_radio # MAV_COMP_ID_TELEMETRY_RADIO
|
||||
bool heartbeat_component_log # MAV_COMP_ID_LOG
|
||||
bool heartbeat_component_osd # MAV_COMP_ID_OSD
|
||||
bool heartbeat_component_obstacle_avoidance # MAV_COMP_ID_OBSTACLE_AVOIDANCE
|
||||
bool heartbeat_component_vio # MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY
|
||||
bool heartbeat_component_pairing_manager # MAV_COMP_ID_PAIRING_MANAGER
|
||||
bool heartbeat_component_udp_bridge # MAV_COMP_ID_UDP_BRIDGE
|
||||
bool heartbeat_component_uart_bridge # MAV_COMP_ID_UART_BRIDGE
|
||||
|
||||
# Misc component health
|
||||
bool avoidance_system_healthy
|
||||
bool open_drone_id_system_healthy
|
||||
bool parachute_system_healthy
|
||||
|
||||
@ -2193,11 +2193,6 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
|
||||
_heartbeat_component_osd = now;
|
||||
break;
|
||||
|
||||
case MAV_COMP_ID_OBSTACLE_AVOIDANCE:
|
||||
_heartbeat_component_obstacle_avoidance = now;
|
||||
_mavlink.telemetry_status().avoidance_system_healthy = (hb.system_status == MAV_STATE_ACTIVE);
|
||||
break;
|
||||
|
||||
case MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY:
|
||||
_heartbeat_component_visual_inertial_odometry = now;
|
||||
break;
|
||||
@ -2909,7 +2904,6 @@ void MavlinkReceiver::CheckHeartbeats(const hrt_abstime &t, bool force)
|
||||
tstatus.heartbeat_component_telemetry_radio = (t <= TIMEOUT + _heartbeat_component_telemetry_radio);
|
||||
tstatus.heartbeat_component_log = (t <= TIMEOUT + _heartbeat_component_log);
|
||||
tstatus.heartbeat_component_osd = (t <= TIMEOUT + _heartbeat_component_osd);
|
||||
tstatus.heartbeat_component_obstacle_avoidance = (t <= TIMEOUT + _heartbeat_component_obstacle_avoidance);
|
||||
tstatus.heartbeat_component_vio = (t <= TIMEOUT + _heartbeat_component_visual_inertial_odometry);
|
||||
tstatus.heartbeat_component_pairing_manager = (t <= TIMEOUT + _heartbeat_component_pairing_manager);
|
||||
tstatus.heartbeat_component_udp_bridge = (t <= TIMEOUT + _heartbeat_component_udp_bridge);
|
||||
|
||||
@ -394,7 +394,6 @@ private:
|
||||
hrt_abstime _heartbeat_component_telemetry_radio{0};
|
||||
hrt_abstime _heartbeat_component_log{0};
|
||||
hrt_abstime _heartbeat_component_osd{0};
|
||||
hrt_abstime _heartbeat_component_obstacle_avoidance{0};
|
||||
hrt_abstime _heartbeat_component_visual_inertial_odometry{0};
|
||||
hrt_abstime _heartbeat_component_pairing_manager{0};
|
||||
hrt_abstime _heartbeat_component_udp_bridge{0};
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user