mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: remove WP_SPEED and WP_RADIUS parameters
AC_WPNav library has equivalent params with very similar names
This commit is contained in:
parent
0351c2ae33
commit
629d23b7e2
@ -2136,8 +2136,9 @@ static void tuning(){
|
||||
if (g.rc_6.control_in < 475) relay.off();
|
||||
break;
|
||||
|
||||
case CH6_TRAVERSE_SPEED:
|
||||
g.waypoint_speed_max = g.rc_6.control_in;
|
||||
case CH6_WP_SPEED:
|
||||
// set waypoint navigation horizontal speed to 0 ~ 1000 cm/s
|
||||
wp_nav.set_horizontal_velocity(g.rc_6.control_in);
|
||||
break;
|
||||
|
||||
case CH6_LOITER_KP:
|
||||
|
@ -211,9 +211,9 @@ public:
|
||||
k_param_command_total,
|
||||
k_param_command_index,
|
||||
k_param_command_nav_index, // remove
|
||||
k_param_waypoint_radius,
|
||||
k_param_waypoint_radius, // remove
|
||||
k_param_circle_radius,
|
||||
k_param_waypoint_speed_max,
|
||||
k_param_waypoint_speed_max, // remove
|
||||
k_param_land_speed,
|
||||
k_param_auto_velocity_z_min,
|
||||
k_param_auto_velocity_z_max, // 219
|
||||
@ -288,9 +288,7 @@ public:
|
||||
//
|
||||
AP_Int8 command_total;
|
||||
AP_Int8 command_index;
|
||||
AP_Int16 waypoint_radius;
|
||||
AP_Int16 circle_radius;
|
||||
AP_Int16 waypoint_speed_max;
|
||||
AP_Int32 rtl_loiter_time;
|
||||
AP_Int16 land_speed;
|
||||
AP_Int16 auto_velocity_z_min; // minimum vertical velocity (i.e. maximum descent) the autopilot may request
|
||||
|
@ -201,15 +201,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
GSCALAR(command_index, "WP_INDEX", 0),
|
||||
|
||||
// @Param: WP_RADIUS
|
||||
// @DisplayName: Waypoint Radius
|
||||
// @Description: Defines the distance from a waypoint, that when crossed indicates the wp has been hit.
|
||||
// @Units: Meters
|
||||
// @Range: 1 127
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS", WP_RADIUS_DEFAULT),
|
||||
|
||||
// @Param: CIRCLE_RADIUS
|
||||
// @DisplayName: Circle radius
|
||||
// @Description: Defines the radius of the circle the vehicle will fly when in Circle flight mode
|
||||
@ -219,14 +210,6 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(circle_radius, "CIRCLE_RADIUS", CIRCLE_RADIUS),
|
||||
|
||||
// @Param: WP_SPEED_MAX
|
||||
// @DisplayName: Waypoint Max Speed Target
|
||||
// @Description: Defines the speed which the aircraft will attempt to maintain during a WP mission.
|
||||
// @Units: Centimeters/Second
|
||||
// @Increment: 100
|
||||
// @User: Standard
|
||||
GSCALAR(waypoint_speed_max, "WP_SPEED_MAX", WAYPOINT_SPEED_MAX),
|
||||
|
||||
// @Param: RTL_LOIT_TIME
|
||||
// @DisplayName: RTL loiter time
|
||||
// @Description: Time (in milliseconds) to loiter above home before begining final descent
|
||||
@ -385,7 +368,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: Channel 6 Tuning
|
||||
// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
|
||||
// @User: Standard
|
||||
// @Values: 0:CH6_NONE,1:CH6_STABILIZE_KP,2:CH6_STABILIZE_KI,3:CH6_YAW_KP,4:CH6_RATE_KP,5:CH6_RATE_KI,6:CH6_YAW_RATE_KP,7:CH6_THROTTLE_KP,8:CH6_TOP_BOTTOM_RATIO,9:CH6_RELAY,10:CH6_TRAVERSE_SPEED,12:CH6_LOITER_KP,13:CH6_HELI_EXTERNAL_GYRO,14:CH6_THR_HOLD_KP,17:CH6_OPTFLOW_KP,18:CH6_OPTFLOW_KI,19:CH6_OPTFLOW_KD,21:CH6_RATE_KD,22:CH6_LOITER_RATE_KP,23:CH6_LOITER_RATE_KD,24:CH6_YAW_KI,25:CH6_ACRO_KP,26:CH6_YAW_RATE_KD,27:CH6_LOITER_KI,28:CH6_LOITER_RATE_KI,29:CH6_STABILIZE_KD,30:CH6_AHRS_YAW_KP,31:CH6_AHRS_KP,32:CH6_INAV_TC,33:CH6_THROTTLE_KI,34:CH6_THR_ACCEL_KP,35:CH6_THR_ACCEL_KI,36:CH6_THR_ACCEL_KD
|
||||
// @Values: 0:CH6_NONE,1:CH6_STABILIZE_KP,2:CH6_STABILIZE_KI,3:CH6_YAW_KP,4:CH6_RATE_KP,5:CH6_RATE_KI,6:CH6_YAW_RATE_KP,7:CH6_THROTTLE_KP,8:CH6_TOP_BOTTOM_RATIO,9:CH6_RELAY,10:CH6_WP_SPEED,12:CH6_LOITER_KP,13:CH6_HELI_EXTERNAL_GYRO,14:CH6_THR_HOLD_KP,17:CH6_OPTFLOW_KP,18:CH6_OPTFLOW_KI,19:CH6_OPTFLOW_KD,21:CH6_RATE_KD,22:CH6_LOITER_RATE_KP,23:CH6_LOITER_RATE_KD,24:CH6_YAW_KI,25:CH6_ACRO_KP,26:CH6_YAW_RATE_KD,27:CH6_LOITER_KI,28:CH6_LOITER_RATE_KI,29:CH6_STABILIZE_KD,30:CH6_AHRS_YAW_KP,31:CH6_AHRS_KP,32:CH6_INAV_TC,33:CH6_THROTTLE_KI,34:CH6_THR_ACCEL_KP,35:CH6_THR_ACCEL_KI,36:CH6_THR_ACCEL_KD
|
||||
GSCALAR(radio_tuning, "TUNE", 0),
|
||||
|
||||
// @Param: TUNE_LOW
|
||||
|
@ -754,7 +754,7 @@ static bool verify_nav_roi()
|
||||
|
||||
static void do_change_speed()
|
||||
{
|
||||
g.waypoint_speed_max = command_cond_queue.p1 * 100;
|
||||
wp_nav.set_horizontal_velocity(command_cond_queue.p1 * 100);
|
||||
}
|
||||
|
||||
static void do_jump()
|
||||
|
@ -1105,10 +1105,6 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation defaults
|
||||
//
|
||||
#ifndef WP_RADIUS_DEFAULT
|
||||
# define WP_RADIUS_DEFAULT 2
|
||||
#endif
|
||||
|
||||
#ifndef CIRCLE_RADIUS
|
||||
# define CIRCLE_RADIUS 10 // meters for circle mode
|
||||
#endif
|
||||
|
@ -161,7 +161,7 @@
|
||||
#define CH6_THR_ACCEL_KD 36 // accel based throttle controller's D term
|
||||
#define CH6_TOP_BOTTOM_RATIO 8 // upper/lower motor ratio (not used)
|
||||
#define CH6_RELAY 9 // switch relay on if ch6 high, off if low
|
||||
#define CH6_TRAVERSE_SPEED 10 // maximum speed to next way point (0 to 10m/s)
|
||||
#define CH6_WP_SPEED 10 // maximum speed to next way point (0 to 10m/s)
|
||||
#define CH6_LOITER_KP 12 // loiter distance controller's P term (position error to speed)
|
||||
#define CH6_LOITER_KI 27 // loiter distance controller's I term (position error to speed)
|
||||
#define CH6_HELI_EXTERNAL_GYRO 13 // TradHeli specific external tail gyro gain
|
||||
|
@ -18,7 +18,7 @@ static void failsafe_radio_on_event()
|
||||
// if throttle is zero disarm motors
|
||||
if (g.rc_3.control_in == 0) {
|
||||
init_disarm_motors();
|
||||
}else if(ap.home_is_set == true && home_distance > g.waypoint_radius) {
|
||||
}else if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) {
|
||||
set_mode(RTL);
|
||||
}else{
|
||||
// We have no GPS or are very close to home so we will land
|
||||
@ -28,7 +28,7 @@ static void failsafe_radio_on_event()
|
||||
case AUTO:
|
||||
// failsafe_throttle is 1 do RTL, 2 means continue with the mission
|
||||
if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_RTL) {
|
||||
if(home_distance > g.waypoint_radius) {
|
||||
if(home_distance > wp_nav.get_waypoint_radius()) {
|
||||
set_mode(RTL);
|
||||
}else{
|
||||
// We are very close to home so we will land
|
||||
@ -38,7 +38,7 @@ static void failsafe_radio_on_event()
|
||||
// if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything
|
||||
break;
|
||||
default:
|
||||
if(ap.home_is_set == true && home_distance > g.waypoint_radius) {
|
||||
if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) {
|
||||
set_mode(RTL);
|
||||
}else{
|
||||
// We have no GPS or are very close to home so we will land
|
||||
@ -77,7 +77,7 @@ static void low_battery_event(void)
|
||||
}
|
||||
break;
|
||||
case AUTO:
|
||||
if(ap.home_is_set == true && home_distance > g.waypoint_radius) {
|
||||
if(ap.home_is_set == true && home_distance > wp_nav.get_waypoint_radius()) {
|
||||
set_mode(RTL);
|
||||
}else{
|
||||
// We have no GPS or are very close to home so we will land
|
||||
|
@ -176,14 +176,6 @@ static void update_nav_mode()
|
||||
*/
|
||||
}
|
||||
|
||||
static bool check_missed_wp()
|
||||
{
|
||||
int32_t temp;
|
||||
temp = wp_bearing - original_wp_bearing;
|
||||
temp = wrap_180_cd(temp);
|
||||
return (labs(temp) > 9000); // we passed the waypoint by 90 degrees
|
||||
}
|
||||
|
||||
// Keeps old data out of our calculation / logs
|
||||
static void reset_nav_params(void)
|
||||
{
|
||||
|
@ -200,9 +200,9 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
||||
int16_t max_speed = 0;
|
||||
|
||||
for(int16_t i = 0; i < 200; i++){
|
||||
int32_t temp = 2 * 100 * (wp_distance - g.waypoint_radius * 100);
|
||||
int32_t temp = 2 * 100 * (wp_distance - wp_nav.get_waypoint_radius());
|
||||
max_speed = sqrtf((float)temp);
|
||||
max_speed = min(max_speed, g.waypoint_speed_max);
|
||||
max_speed = min(max_speed, wp_nav.get_horizontal_speed());
|
||||
cliSerial->printf("Zspeed: %ld, %d, %ld\n", temp, max_speed, wp_distance);
|
||||
wp_distance += 100;
|
||||
}
|
||||
@ -724,8 +724,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
|
||||
cliSerial->printf_P(PSTR("%d wp\n"), (int)g.command_total);
|
||||
cliSerial->printf_P(PSTR("Hit rad: %dm\n"), (int)g.waypoint_radius);
|
||||
//cliSerial->printf_P(PSTR("Loiter radius: %d\n\n"), (int)g.loiter_radius);
|
||||
cliSerial->printf_P(PSTR("Hit rad: %dm\n"), (int)wp_nav.get_waypoint_radius());
|
||||
|
||||
report_wp();
|
||||
|
||||
@ -1017,7 +1016,7 @@ test_logging(uint8_t argc, const Menu::arg *argv)
|
||||
*
|
||||
* g.rtl_altitude.set_and_save(300);
|
||||
* g.command_total.set_and_save(4);
|
||||
* g.waypoint_radius.set_and_save(3);
|
||||
* wp_nav.set_waypoint_radius(300);
|
||||
*
|
||||
* test_wp(NULL, NULL);
|
||||
* return (0);
|
||||
|
Loading…
Reference in New Issue
Block a user