APM:Libraries
AP_VisualOdom_Backend.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_VisualOdom_Backend.h"
17 
18 /*
19  base class constructor.
20  This incorporates initialisation as well.
21 */
23  _frontend(frontend)
24 {
25 }
26 
27 // set deltas (used by backend to update state)
28 void AP_VisualOdom_Backend::set_deltas(const Vector3f &angle_delta, const Vector3f& position_delta, uint64_t time_delta_usec, float confidence)
29 {
30  // rotate and store angle_delta
31  _frontend._state.angle_delta = angle_delta;
33 
34  // rotate and store position_delta
35  _frontend._state.position_delta = position_delta;
37 
38  _frontend._state.time_delta_usec = time_delta_usec;
39  _frontend._state.confidence = confidence;
41 }
AP_VisualOdom_Backend(AP_VisualOdom &frontend)
void set_deltas(const Vector3f &angle_delta, const Vector3f &position_delta, uint64_t time_delta_usec, float confidence)
Rotation
Definition: rotations.h:27
uint32_t millis()
Definition: system.cpp:157
VisualOdomState _state
Definition: AP_VisualOdom.h:84
void rotate(enum Rotation rotation)
Definition: vector3.cpp:28
AP_Int8 _orientation
Definition: AP_VisualOdom.h:78