CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_WPNav/AC_WPNav_OA.h
Views: 1798
1
#pragma once
2
3
#include "AC_WPNav_config.h"
4
5
#if AC_WPNAV_OA_ENABLED
6
7
#include <AC_WPNav/AC_WPNav.h>
8
#include <AC_Avoidance/AP_OAPathPlanner.h>
9
#include <AC_Avoidance/AP_OABendyRuler.h>
10
11
class AC_WPNav_OA : public AC_WPNav
12
{
13
14
public:
15
/// Constructor
16
AC_WPNav_OA(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
17
18
// returns object avoidance adjusted wp location using location class
19
// returns false if unable to convert from target vector to global coordinates
20
bool get_oa_wp_destination(Location& destination) const override;
21
22
/// set_wp_destination waypoint using position vector (distance from ekf origin in cm)
23
/// terrain_alt should be true if destination.z is a desired altitude above terrain
24
/// returns false on failure (likely caused by missing terrain data)
25
bool set_wp_destination(const Vector3f& destination, bool terrain_alt = false) override;
26
27
/// get horizontal distance to destination in cm
28
/// always returns distance to final destination (i.e. does not use oa adjusted destination)
29
float get_wp_distance_to_destination() const override;
30
31
/// get bearing to next waypoint in centi-degrees
32
/// always returns bearing to final destination (i.e. does not use oa adjusted destination)
33
int32_t get_wp_bearing_to_destination() const override;
34
35
/// true when we have come within RADIUS cm of the final destination
36
bool reached_wp_destination() const override;
37
38
/// run the wp controller
39
bool update_wpnav() override;
40
41
protected:
42
43
// oa path planning variables
44
AP_OAPathPlanner::OA_RetState _oa_state; // state of object avoidance, if OA_SUCCESS we use _oa_destination to avoid obstacles
45
Vector3f _origin_oabak; // backup of _origin so it can be restored when oa completes
46
Vector3f _destination_oabak; // backup of _destination so it can be restored when oa completes
47
Vector3f _next_destination_oabak;// backup of _next_destination so it can be restored when oa completes
48
bool _terrain_alt_oabak; // true if backup origin and destination z-axis are terrain altitudes
49
Location _oa_destination; // intermediate destination during avoidance
50
Location _oa_next_destination; // intermediate next destination during avoidance
51
};
52
53
#endif // AC_WPNAV_OA_ENABLED
54
55