mirror of https://github.com/ArduPilot/ardupilot
Copter: add WP_YAW_BEHAVE parameter
Allows user to control whether nose points towards next waypoint and/or home when RTLing. Replaces YAW_OVR_BEHAVE which had a very similar purpose. Almost nobody ever knew about or used this parameter.
This commit is contained in:
parent
18c1373847
commit
0fc9c8739e
|
@ -78,7 +78,7 @@ public:
|
||||||
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
|
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
|
||||||
k_param_rssi_pin,
|
k_param_rssi_pin,
|
||||||
k_param_throttle_accel_enabled,
|
k_param_throttle_accel_enabled,
|
||||||
k_param_yaw_override_behaviour,
|
k_param_wp_yaw_behavior,
|
||||||
k_param_acro_trainer_enabled,
|
k_param_acro_trainer_enabled,
|
||||||
k_param_pilot_velocity_z_max, // 28
|
k_param_pilot_velocity_z_max, // 28
|
||||||
|
|
||||||
|
@ -282,7 +282,7 @@ public:
|
||||||
AP_Int8 battery_curr_pin;
|
AP_Int8 battery_curr_pin;
|
||||||
AP_Int8 rssi_pin;
|
AP_Int8 rssi_pin;
|
||||||
AP_Int8 throttle_accel_enabled; // enable/disable accel based throttle controller
|
AP_Int8 throttle_accel_enabled; // enable/disable accel based throttle controller
|
||||||
AP_Int8 yaw_override_behaviour; // controls when autopilot takes back normal control of yaw after pilot overrides
|
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
|
||||||
|
|
||||||
// Waypoints
|
// Waypoints
|
||||||
//
|
//
|
||||||
|
|
|
@ -182,12 +182,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(throttle_accel_enabled, "THR_ACC_ENABLE", 1),
|
GSCALAR(throttle_accel_enabled, "THR_ACC_ENABLE", 1),
|
||||||
|
|
||||||
// @Param: YAW_OVR_BEHAVE
|
// @Param: WP_YAW_BEHAVIOR
|
||||||
// @DisplayName: Yaw override behaviour
|
// @DisplayName: Yaw behaviour during missions
|
||||||
// @Description: Controls when autopilot takes back normal control of yaw after pilot overrides
|
// @Description: Determines how the autopilot controls the yaw during missions and RTL
|
||||||
// @Values: 0:At Next WP, 1:On Mission Restart
|
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(yaw_override_behaviour, "YAW_OVR_BEHAVE", YAW_OVERRIDE_BEHAVIOUR_AT_NEXT_WAYPOINT),
|
GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP),
|
||||||
|
|
||||||
// @Param: WP_TOTAL
|
// @Param: WP_TOTAL
|
||||||
// @DisplayName: Waypoint Total
|
// @DisplayName: Waypoint Total
|
||||||
|
|
|
@ -279,7 +279,7 @@ static void do_nav_wp()
|
||||||
loiter_time_max = command_nav_queue.p1;
|
loiter_time_max = command_nav_queue.p1;
|
||||||
|
|
||||||
// reset control of yaw to default
|
// reset control of yaw to default
|
||||||
if( g.yaw_override_behaviour == YAW_OVERRIDE_BEHAVIOUR_AT_NEXT_WAYPOINT ) {
|
if( g.wp_yaw_behavior == WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP || g.wp_yaw_behavior == WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL) {
|
||||||
set_yaw_mode(AUTO_YAW);
|
set_yaw_mode(AUTO_YAW);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -516,8 +516,9 @@ static bool verify_RTL()
|
||||||
rtl_state = RTL_STATE_INITIAL_CLIMB;
|
rtl_state = RTL_STATE_INITIAL_CLIMB;
|
||||||
}else{
|
}else{
|
||||||
// point nose towards home
|
// point nose towards home
|
||||||
// To-Do: make this user configurable whether RTL points towards home or not
|
if(g.wp_yaw_behavior == WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP) {
|
||||||
set_yaw_mode(RTL_YAW);
|
set_yaw_mode(RTL_YAW);
|
||||||
|
}
|
||||||
|
|
||||||
// Set wp navigation target to above home
|
// Set wp navigation target to above home
|
||||||
wp_nav.set_destination(Vector3f(0,0,get_RTL_alt()));
|
wp_nav.set_destination(Vector3f(0,0,get_RTL_alt()));
|
||||||
|
|
|
@ -187,9 +187,10 @@
|
||||||
#define NAV_WP 3
|
#define NAV_WP 3
|
||||||
#define NAV_WP_INAV 5
|
#define NAV_WP_INAV 5
|
||||||
|
|
||||||
// Yaw override behaviours - used for setting yaw_override_behaviour
|
// Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter
|
||||||
#define YAW_OVERRIDE_BEHAVIOUR_AT_NEXT_WAYPOINT 0 // auto pilot takes back yaw control at next waypoint
|
#define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received)
|
||||||
#define YAW_OVERRIDE_BEHAVIOUR_AT_MISSION_RESTART 1 // auto pilot tkaes back control only when mission is restarted
|
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl
|
||||||
|
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last
|
||||||
|
|
||||||
// TOY mixing options
|
// TOY mixing options
|
||||||
#define TOY_LOOKUP_TABLE 0
|
#define TOY_LOOKUP_TABLE 0
|
||||||
|
|
Loading…
Reference in New Issue