Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_WPNav/AC_WPNav_OA.h
Views: 1798
#pragma once12#include "AC_WPNav_config.h"34#if AC_WPNAV_OA_ENABLED56#include <AC_WPNav/AC_WPNav.h>7#include <AC_Avoidance/AP_OAPathPlanner.h>8#include <AC_Avoidance/AP_OABendyRuler.h>910class AC_WPNav_OA : public AC_WPNav11{1213public:14/// Constructor15AC_WPNav_OA(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);1617// returns object avoidance adjusted wp location using location class18// returns false if unable to convert from target vector to global coordinates19bool get_oa_wp_destination(Location& destination) const override;2021/// set_wp_destination waypoint using position vector (distance from ekf origin in cm)22/// terrain_alt should be true if destination.z is a desired altitude above terrain23/// returns false on failure (likely caused by missing terrain data)24bool set_wp_destination(const Vector3f& destination, bool terrain_alt = false) override;2526/// get horizontal distance to destination in cm27/// always returns distance to final destination (i.e. does not use oa adjusted destination)28float get_wp_distance_to_destination() const override;2930/// get bearing to next waypoint in centi-degrees31/// always returns bearing to final destination (i.e. does not use oa adjusted destination)32int32_t get_wp_bearing_to_destination() const override;3334/// true when we have come within RADIUS cm of the final destination35bool reached_wp_destination() const override;3637/// run the wp controller38bool update_wpnav() override;3940protected:4142// oa path planning variables43AP_OAPathPlanner::OA_RetState _oa_state; // state of object avoidance, if OA_SUCCESS we use _oa_destination to avoid obstacles44Vector3f _origin_oabak; // backup of _origin so it can be restored when oa completes45Vector3f _destination_oabak; // backup of _destination so it can be restored when oa completes46Vector3f _next_destination_oabak;// backup of _next_destination so it can be restored when oa completes47bool _terrain_alt_oabak; // true if backup origin and destination z-axis are terrain altitudes48Location _oa_destination; // intermediate destination during avoidance49Location _oa_next_destination; // intermediate next destination during avoidance50};5152#endif // AC_WPNAV_OA_ENABLED535455