12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576 |
- #include "AP_RangeFinder_MAVLink.h"
- #include <AP_HAL/AP_HAL.h>
- extern const AP_HAL::HAL& hal;
- AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
- AP_RangeFinder_Backend(_state, _params)
- {
- state.last_reading_ms = AP_HAL::millis();
- distance_cm = 0;
- }
- bool AP_RangeFinder_MAVLink::detect()
- {
-
-
- return true;
- }
- void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg)
- {
- mavlink_distance_sensor_t packet;
- mavlink_msg_distance_sensor_decode(&msg, &packet);
-
- if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) {
- state.last_reading_ms = AP_HAL::millis();
- distance_cm = packet.current_distance;
- }
- sensor_type = (MAV_DISTANCE_SENSOR)packet.type;
- }
- void AP_RangeFinder_MAVLink::update(void)
- {
-
-
- if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) {
- set_status(RangeFinder::RangeFinder_NoData);
- state.distance_cm = 0;
- } else {
- state.distance_cm = distance_cm;
- update_status();
- }
- }
|