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_Circle.h
Views: 1798
1
#pragma once
2
3
#include <AP_Common/AP_Common.h>
4
#include <AP_Param/AP_Param.h>
5
#include <AP_Math/AP_Math.h>
6
#include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
7
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library
8
9
// loiter maximum velocities and accelerations
10
#define AC_CIRCLE_RADIUS_DEFAULT 1000.0f // radius of the circle in cm that the vehicle will fly
11
#define AC_CIRCLE_RATE_DEFAULT 20.0f // turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise
12
#define AC_CIRCLE_ANGULAR_ACCEL_MIN 2.0f // angular acceleration should never be less than 2deg/sec
13
#define AC_CIRCLE_RADIUS_MAX 200000.0f // maximum allowed circle radius of 2km
14
15
class AC_Circle
16
{
17
public:
18
19
/// Constructor
20
AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control);
21
22
/// init - initialise circle controller setting center specifically
23
/// set terrain_alt to true if center.z should be interpreted as an alt-above-terrain. Rate should be +ve in deg/sec for cw turn
24
/// caller should set the position controller's x,y and z speeds and accelerations before calling this
25
void init(const Vector3p& center, bool terrain_alt, float rate_deg_per_sec);
26
27
/// init - initialise circle controller setting center using stopping point and projecting out based on the copter's heading
28
/// caller should set the position controller's x,y and z speeds and accelerations before calling this
29
void init();
30
31
/// set circle center to a Location
32
void set_center(const Location& center);
33
34
/// set_circle_center as a vector from ekf origin
35
/// terrain_alt should be true if center.z is alt is above terrain
36
void set_center(const Vector3f& center, bool terrain_alt) { _center = center.topostype(); _terrain_alt = terrain_alt; }
37
38
/// get_circle_center in cm from home
39
const Vector3p& get_center() const { return _center; }
40
41
/// returns true if using terrain altitudes
42
bool center_is_terrain_alt() const { return _terrain_alt; }
43
44
/// get_radius - returns radius of circle in cm
45
float get_radius() const { return is_positive(_radius)?_radius:_radius_parm; }
46
47
/// set_radius_cm - sets circle radius in cm
48
void set_radius_cm(float radius_cm);
49
50
/// get_rate - returns target rate in deg/sec held in RATE parameter
51
float get_rate() const { return _rate; }
52
53
/// get_rate_current - returns actual calculated rate target in deg/sec, which may be less than _rate
54
float get_rate_current() const { return ToDeg(_angular_vel); }
55
56
/// set_rate - set circle rate in degrees per second
57
void set_rate(float deg_per_sec);
58
59
/// get_angle_total - return total angle in radians that vehicle has circled
60
float get_angle_total() const { return _angle_total; }
61
62
/// update - update circle controller
63
/// returns false on failure which indicates a terrain failsafe
64
bool update(float climb_rate_cms = 0.0f) WARN_IF_UNUSED;
65
66
/// get desired roll, pitch which should be fed into stabilize controllers
67
float get_roll() const { return _pos_control.get_roll_cd(); }
68
float get_pitch() const { return _pos_control.get_pitch_cd(); }
69
Vector3f get_thrust_vector() const { return _pos_control.get_thrust_vector(); }
70
float get_yaw() const { return _yaw; }
71
72
/// returns true if update has been run recently
73
/// used by vehicle code to determine if get_yaw() is valid
74
bool is_active() const;
75
76
// get_closest_point_on_circle - returns closest point on the circle
77
// circle's center should already have been set
78
// closest point on the circle will be placed in result, dist_cm will be updated with the distance to the center
79
// result's altitude (i.e. z) will be set to the circle_center's altitude
80
// if vehicle is at the center of the circle, the edge directly behind vehicle will be returned
81
void get_closest_point_on_circle(Vector3f& result, float& dist_cm) const;
82
83
/// get horizontal distance to loiter target in cm
84
float get_distance_to_target() const { return _pos_control.get_pos_error_xy_cm(); }
85
86
/// get bearing to target in centi-degrees
87
int32_t get_bearing_to_target() const { return _pos_control.get_bearing_to_target_cd(); }
88
89
/// true if pilot control of radius and turn rate is enabled
90
bool pilot_control_enabled() const { return (_options.get() & CircleOptions::MANUAL_CONTROL) != 0; }
91
92
/// true if mount roi is at circle center
93
bool roi_at_center() const { return (_options.get() & CircleOptions::ROI_AT_CENTER) != 0; }
94
95
/// provide rangefinder based terrain offset
96
/// terrain offset is the terrain's height above the EKF origin
97
void set_rangefinder_terrain_offset(bool use, bool healthy, float terrain_offset_cm) { _rangefinder_available = use; _rangefinder_healthy = healthy; _rangefinder_terrain_offset_cm = terrain_offset_cm;}
98
99
/// check for a change in the radius params
100
void check_param_change();
101
102
static const struct AP_Param::GroupInfo var_info[];
103
104
private:
105
106
// calc_velocities - calculate angular velocity max and acceleration based on radius and rate
107
// this should be called whenever the radius or rate are changed
108
// initialises the yaw and current position around the circle
109
// init_velocity should be set true if vehicle is just starting circle
110
void calc_velocities(bool init_velocity);
111
112
// init_start_angle - sets the starting angle around the circle and initialises the angle_total
113
// if use_heading is true the vehicle's heading will be used to init the angle causing minimum yaw movement
114
// if use_heading is false the vehicle's position from the center will be used to initialise the angle
115
void init_start_angle(bool use_heading);
116
117
// get expected source of terrain data
118
enum class TerrainSource {
119
TERRAIN_UNAVAILABLE,
120
TERRAIN_FROM_RANGEFINDER,
121
TERRAIN_FROM_TERRAINDATABASE,
122
};
123
AC_Circle::TerrainSource get_terrain_source() const;
124
125
// get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude)
126
bool get_terrain_offset(float& offset_cm);
127
128
// flags structure
129
struct circle_flags {
130
uint8_t panorama : 1; // true if we are doing a panorama
131
} _flags;
132
133
// references to inertial nav and ahrs libraries
134
const AP_InertialNav& _inav;
135
const AP_AHRS_View& _ahrs;
136
AC_PosControl& _pos_control;
137
138
enum CircleOptions {
139
MANUAL_CONTROL = 1U << 0,
140
FACE_DIRECTION_OF_TRAVEL = 1U << 1,
141
INIT_AT_CENTER = 1U << 2, // true then the circle center will be the current location, false and the center will be 1 radius ahead
142
ROI_AT_CENTER = 1U << 3, // true when the mount roi is at circle center
143
};
144
145
// parameters
146
AP_Float _radius_parm; // radius of circle in cm loaded from params
147
AP_Float _rate_parm; // rotation speed in deg/sec
148
AP_Int16 _options; // stick control enable/disable
149
150
// internal variables
151
Vector3p _center; // center of circle in cm from home
152
float _radius; // radius of circle in cm
153
float _rate; // rotation speed of circle in deg/sec. +ve for cw turn
154
float _yaw; // yaw heading (normally towards circle center)
155
float _angle; // current angular position around circle in radians (0=directly north of the center of the circle)
156
float _angle_total; // total angle travelled in radians
157
float _angular_vel; // angular velocity in radians/sec
158
float _angular_vel_max; // maximum velocity in radians/sec
159
float _angular_accel; // angular acceleration in radians/sec/sec
160
uint32_t _last_update_ms; // system time of last update
161
float _last_radius_param; // last value of radius param, used to update radius on param change
162
163
// terrain following variables
164
bool _terrain_alt; // true if _center.z is alt-above-terrain, false if alt-above-ekf-origin
165
bool _rangefinder_available; // true if range finder could be used
166
bool _rangefinder_healthy; // true if range finder is healthy
167
float _rangefinder_terrain_offset_cm; // latest rangefinder based terrain offset (e.g. terrain's height above EKF origin)
168
};
169
170