60 mavlink_distance_sensor_t packet;
61 mavlink_msg_distance_sensor_decode(msg, &packet);
64 if (packet.orientation <= MAV_SENSOR_ROTATION_YAW_315) {
65 uint8_t sector = packet.orientation;
66 _angle[sector] = sector * 45;
67 _distance[sector] = packet.current_distance / 100.0f;
76 if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_90) {
bool _distance_valid[PROXIMITY_SECTORS_MAX]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
float _angle[PROXIMITY_SECTORS_MAX]
void set_status(AP_Proximity::Proximity_Status status)
#define PROXIMITY_MAV_TIMEOUT_MS
bool get_upward_distance(float &distance) const
float _distance[PROXIMITY_SECTORS_MAX]
uint32_t _last_upward_update_ms
void handle_msg(mavlink_message_t *msg) override
void update_boundary_for_sector(uint8_t sector)
AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)