APM:Libraries
AP_Proximity_MAV.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_HAL/AP_HAL.h>
17 #include "AP_Proximity_MAV.h"
19 #include <ctype.h>
20 #include <stdio.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 /*
25  The constructor also initialises the proximity sensor. Note that this
26  constructor is not called until detect() returns true, so we
27  already know that we should setup the proximity sensor
28 */
31  AP_Proximity_Backend(_frontend, _state)
32 {
33 }
34 
35 // update the state of the sensor
37 {
38  // check for timeout and set health status
42  } else {
44  }
45 }
46 
47 // get distance upwards in meters. returns true on success
49 {
51  distance = _distance_upward;
52  return true;
53  }
54  return false;
55 }
56 
57 // handle mavlink DISTANCE_SENSOR messages
58 void AP_Proximity_MAV::handle_msg(mavlink_message_t *msg)
59 {
60  mavlink_distance_sensor_t packet;
61  mavlink_msg_distance_sensor_decode(msg, &packet);
62 
63  // store distance to appropriate sector based on orientation field
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;
68  _distance_min = packet.min_distance / 100.0f;
69  _distance_max = packet.max_distance / 100.0f;
70  _distance_valid[sector] = (_distance[sector] >= _distance_min) && (_distance[sector] <= _distance_max);
73  }
74 
75  // store upward distance
76  if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_90) {
77  _distance_upward = packet.current_distance / 100.0f;
79  }
80 }
bool _distance_valid[PROXIMITY_SECTORS_MAX]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
float _angle[PROXIMITY_SECTORS_MAX]
void set_status(AP_Proximity::Proximity_Status status)
float distance
Definition: location.cpp:94
#define PROXIMITY_MAV_TIMEOUT_MS
bool get_upward_distance(float &distance) const
float _distance[PROXIMITY_SECTORS_MAX]
uint32_t _last_upward_update_ms
uint32_t millis()
Definition: system.cpp:157
uint32_t _last_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)