APM:Libraries
AP_VisualOdom_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_VisualOdom_MAV.h"
19 
20 extern const AP_HAL::HAL& hal;
21 
22 // constructor
24  AP_VisualOdom_Backend(frontend)
25 {
26 }
27 
28 // consume VISIOIN_POSITION_DELTA MAVLink message
29 void AP_VisualOdom_MAV::handle_msg(mavlink_message_t *msg)
30 {
31  // decode message
32  mavlink_vision_position_delta_t packet;
33  mavlink_msg_vision_position_delta_decode(msg, &packet);
34 
35  const Vector3f angle_delta(packet.angle_delta[0], packet.angle_delta[1], packet.angle_delta[2]);
36  const Vector3f position_delta(packet.position_delta[0], packet.position_delta[1], packet.position_delta[2]);
37  set_deltas(angle_delta, position_delta, packet.time_delta_usec, packet.confidence);
38 }
void set_deltas(const Vector3f &angle_delta, const Vector3f &position_delta, uint64_t time_delta_usec, float confidence)
AP_VisualOdom_MAV(AP_VisualOdom &frontend)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void handle_msg(mavlink_message_t *msg) override