mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_WPNav: allow setting of horizontal velocity
Also added accessor function for waypoint radius parameter
This commit is contained in:
parent
b58c26bcd5
commit
0351c2ae33
@ -8,11 +8,13 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
|
||||
// index 0 was used for the old orientation matrix
|
||||
|
||||
// @Param: SPEED
|
||||
// @DisplayName: Speed in cm/s to travel between waypoints
|
||||
// @Description: The desired horizontal speed in cm/s while travelling between waypoints
|
||||
// @DisplayName: Waypoint Speed Target
|
||||
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain during a WP mission
|
||||
// @Units: Centimeters/Second
|
||||
// @Range: 0 1000
|
||||
// @Increment: 50
|
||||
AP_GROUPINFO("SPEED", 0, AC_WPNav, _speed_cms, WPNAV_WP_SPEED),
|
||||
// @Increment: 100
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED", 0, AC_WPNav, _speed_cms, WPNAV_WP_SPEED),
|
||||
|
||||
// @Param: RADIUS
|
||||
// @DisplayName: Waypoint Radius
|
||||
@ -21,7 +23,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
|
||||
// @Range: 100 1000
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS),
|
||||
AP_GROUPINFO("RADIUS", 1, AC_WPNav, _wp_radius_cm, WPNAV_WP_RADIUS),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -6,8 +6,6 @@
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Math.h>
|
||||
#include <AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_Baro.h> // ArduPilot Mega Barometer Library
|
||||
#include <AC_PID.h> // PID library
|
||||
#include <APM_PI.h> // PID library
|
||||
#include <AP_InertialNav.h> // Inertial Navigation library
|
||||
@ -138,9 +136,15 @@ public:
|
||||
_cos_roll = cos_roll;
|
||||
}
|
||||
|
||||
/// set_horizontal_velocity - allows main code to pass target horizontal velocity for wp navigation
|
||||
void set_horizontal_velocity(float velocity_cms) { _speed_cms = velocity_cms; };
|
||||
|
||||
/// set_climb_velocity - allows main code to pass max climb velocity to wp navigation
|
||||
void set_climb_velocity(float velocity_cms) { _speedz_cms = velocity_cms; };
|
||||
|
||||
/// get_waypoint_radius - access for waypoint radius in cm
|
||||
float get_waypoint_radius() { return _wp_radius_cm; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
protected:
|
||||
|
Loading…
Reference in New Issue
Block a user