2018-09-07 01:23:33 -03:00
# include "Copter.h"
# if MODE_ZIGZAG_ENABLED == ENABLED
/*
* Init and run calls for zigzag flight mode
*/
2018-09-29 06:25:31 -03:00
# define ZIGZAG_WP_RADIUS_CM 300
2020-04-07 12:23:27 -03:00
# define ZIGZAG_LINE_INFINITY -1
2018-09-07 01:23:33 -03:00
2020-05-11 23:17:21 -03:00
const AP_Param : : GroupInfo ModeZigZag : : var_info [ ] = {
// @Param: AUTO_ENABLE
// @DisplayName: ZigZag auto enable/disable
// @Description: Allows you to enable (1) or disable (0) ZigZag auto feature
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO_FLAGS ( " AUTO_ENABLE " , 1 , ModeZigZag , _auto_enabled , 0 , AP_PARAM_FLAG_ENABLE ) ,
2022-11-01 00:11:31 -03:00
# if HAL_SPRAYER_ENABLED
2020-05-11 23:17:21 -03:00
// @Param: SPRAYER
// @DisplayName: Auto sprayer in ZigZag
// @Description: Enable the auto sprayer in ZigZag mode. SPRAY_ENABLE = 1 and SERVOx_FUNCTION = 22(SprayerPump) / 23(SprayerSpinner) also must be set. This makes the sprayer on while moving to destination A or B. The sprayer will stop if the vehicle reaches destination or the flight mode is changed from ZigZag to other.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO ( " SPRAYER " , 2 , ModeZigZag , _spray_enabled , 0 ) ,
2022-11-01 00:11:31 -03:00
# endif // HAL_SPRAYER_ENABLED
2020-05-11 23:17:21 -03:00
// @Param: WP_DELAY
// @DisplayName: The delay for zigzag waypoint
// @Description: Waiting time after reached the destination
// @Units: s
2021-11-03 23:55:53 -03:00
// @Range: 0 127
2020-05-11 23:17:21 -03:00
// @User: Advanced
2021-11-03 23:55:53 -03:00
AP_GROUPINFO ( " WP_DELAY " , 3 , ModeZigZag , _wp_delay , 0 ) ,
2020-05-11 23:17:21 -03:00
// @Param: SIDE_DIST
// @DisplayName: Sideways distance in ZigZag auto
// @Description: The distance to move sideways in ZigZag mode
// @Units: m
// @Range: 0.1 100
// @User: Advanced
AP_GROUPINFO ( " SIDE_DIST " , 4 , ModeZigZag , _side_dist , 4 ) ,
// @Param: DIRECTION
// @DisplayName: Sideways direction in ZigZag auto
// @Description: The direction to move sideways in ZigZag mode
// @Values: 0:forward, 1:right, 2:backward, 3:left
// @User: Advanced
AP_GROUPINFO ( " DIRECTION " , 5 , ModeZigZag , _direction , 0 ) ,
// @Param: LINE_NUM
// @DisplayName: Total number of lines
// @Description: Total number of lines for ZigZag auto if 1 or more. -1: Infinity, 0: Just moving to sideways
// @Range: -1 32767
// @User: Advanced
AP_GROUPINFO ( " LINE_NUM " , 6 , ModeZigZag , _line_num , 0 ) ,
AP_GROUPEND
} ;
ModeZigZag : : ModeZigZag ( void ) : Mode ( )
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
2018-09-29 06:25:31 -03:00
// initialise zigzag controller
2019-05-09 23:18:49 -03:00
bool ModeZigZag : : init ( bool ignore_checks )
2018-09-07 01:23:33 -03:00
{
2020-02-05 22:33:15 -04:00
if ( ! copter . failsafe . radio ) {
// apply simple mode transform to pilot inputs
update_simple_mode ( ) ;
// convert pilot input to lean angles
float target_roll , target_pitch ;
2021-09-06 06:44:18 -03:00
get_pilot_desired_lean_angles ( target_roll , target_pitch , loiter_nav - > get_angle_max_cd ( ) , attitude_control - > get_althold_lean_angle_max_cd ( ) ) ;
2020-02-05 22:33:15 -04:00
// process pilot's roll and pitch input
2021-05-11 01:42:02 -03:00
loiter_nav - > set_pilot_desired_acceleration ( target_roll , target_pitch ) ;
2020-02-05 22:33:15 -04:00
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs and we do not switch to RTL for some reason
loiter_nav - > clear_pilot_desired_acceleration ( ) ;
}
2018-09-07 01:23:33 -03:00
loiter_nav - > init_target ( ) ;
2021-07-08 01:17:41 -03:00
// set vertical speed and acceleration limits
pos_control - > set_max_speed_accel_z ( - get_pilot_speed_dn ( ) , g . pilot_speed_up , g . pilot_accel_z ) ;
pos_control - > set_correction_speed_accel_z ( - get_pilot_speed_dn ( ) , g . pilot_speed_up , g . pilot_accel_z ) ;
2021-05-19 11:07:38 -03:00
// initialise the vertical position controller
2018-09-07 01:23:33 -03:00
if ( ! pos_control - > is_active_z ( ) ) {
2021-05-11 01:42:02 -03:00
pos_control - > init_z_controller ( ) ;
2018-09-07 01:23:33 -03:00
}
// initialise waypoint state
2018-09-29 06:25:31 -03:00
stage = STORING_POINTS ;
dest_A . zero ( ) ;
dest_B . zero ( ) ;
2020-04-07 12:23:27 -03:00
// initialize zigzag auto
init_auto ( ) ;
2020-04-03 04:51:59 -03:00
2018-09-29 06:25:31 -03:00
return true ;
2018-09-07 01:23:33 -03:00
}
2020-03-25 23:22:23 -03:00
// perform cleanup required when leaving zigzag mode
void ModeZigZag : : exit ( )
{
2020-04-03 01:38:35 -03:00
// The sprayer will stop if the flight mode is changed from ZigZag to other
spray ( false ) ;
2020-03-25 23:22:23 -03:00
}
2018-09-29 06:25:31 -03:00
// run the zigzag controller
2018-09-07 01:23:33 -03:00
// should be called at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeZigZag : : run ( )
2018-09-07 01:23:33 -03:00
{
2021-05-19 11:07:38 -03:00
// set vertical speed and acceleration limits
2021-05-11 01:42:02 -03:00
pos_control - > set_max_speed_accel_z ( - get_pilot_speed_dn ( ) , g . pilot_speed_up , g . pilot_accel_z ) ;
2018-09-07 01:23:33 -03:00
2020-04-03 04:51:59 -03:00
// set the direction and the total number of lines
2020-05-11 23:17:21 -03:00
zigzag_direction = ( Direction ) constrain_int16 ( _direction , 0 , 3 ) ;
2021-05-04 04:08:27 -03:00
line_num = constrain_int16 ( _line_num , ZIGZAG_LINE_INFINITY , 32767 ) ;
2020-04-03 01:48:23 -03:00
2018-09-29 06:25:31 -03:00
// auto control
if ( stage = = AUTO ) {
2020-02-05 22:33:15 -04:00
if ( is_disarmed_or_landed ( ) | | ! motors - > get_interlock ( ) ) {
// vehicle should be under manual control when disarmed or landed
return_to_manual_control ( false ) ;
} else if ( reached_destination ( ) ) {
2020-04-03 01:48:23 -03:00
// if vehicle has reached destination switch to manual control or moving to A or B
2018-09-29 06:25:31 -03:00
AP_Notify : : events . waypoint_complete = 1 ;
2020-04-03 01:48:23 -03:00
if ( is_auto ) {
2020-04-07 12:23:27 -03:00
if ( line_num = = ZIGZAG_LINE_INFINITY | | line_count < line_num ) {
2020-04-03 04:51:59 -03:00
if ( auto_stage = = AutoState : : SIDEWAYS ) {
save_or_move_to_destination ( ( ab_dest_stored = = Destination : : A ) ? Destination : : B : Destination : : A ) ;
} else {
// spray off
spray ( false ) ;
move_to_side ( ) ;
}
2020-04-03 01:48:23 -03:00
} else {
2020-04-07 12:23:27 -03:00
init_auto ( ) ;
2020-04-03 04:51:59 -03:00
return_to_manual_control ( true ) ;
2020-04-03 01:48:23 -03:00
}
} else {
return_to_manual_control ( true ) ;
}
2018-09-07 01:23:33 -03:00
} else {
auto_control ( ) ;
}
}
2018-09-29 06:25:31 -03:00
// manual control
if ( stage = = STORING_POINTS | | stage = = MANUAL_REGAIN ) {
// receive pilot's inputs, do position and attitude control
manual_control ( ) ;
}
}
2020-02-22 09:58:42 -04:00
// save current position as A or B. If both A and B have been saved move to the one specified
void ModeZigZag : : save_or_move_to_destination ( Destination ab_dest )
2018-09-29 06:25:31 -03:00
{
// get current position as an offset from EKF origin
2021-10-20 05:29:57 -03:00
const Vector2f curr_pos { inertial_nav . get_position_xy_cm ( ) } ;
2018-09-29 06:25:31 -03:00
// handle state machine changes
switch ( stage ) {
case STORING_POINTS :
2020-02-22 09:58:42 -04:00
if ( ab_dest = = Destination : : A ) {
2018-09-29 06:25:31 -03:00
// store point A
2021-09-11 05:07:42 -03:00
dest_A = curr_pos ;
2018-09-29 06:25:31 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " ZigZag: point A stored " ) ;
2019-10-25 03:06:05 -03:00
AP : : logger ( ) . Write_Event ( LogEvent : : ZIGZAG_STORE_A ) ;
2018-09-29 06:25:31 -03:00
} else {
// store point B
2021-09-11 05:07:42 -03:00
dest_B = curr_pos ;
2018-09-29 06:25:31 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " ZigZag: point B stored " ) ;
2019-10-25 03:06:05 -03:00
AP : : logger ( ) . Write_Event ( LogEvent : : ZIGZAG_STORE_B ) ;
2018-09-29 06:25:31 -03:00
}
// if both A and B have been stored advance state
2020-04-03 01:48:23 -03:00
if ( ! dest_A . is_zero ( ) & & ! dest_B . is_zero ( ) & & ! is_zero ( ( dest_B - dest_A ) . length_squared ( ) ) ) {
2018-09-29 06:25:31 -03:00
stage = MANUAL_REGAIN ;
2020-04-03 01:38:35 -03:00
spray ( false ) ;
2020-04-03 01:48:23 -03:00
} else if ( ! dest_A . is_zero ( ) | | ! dest_B . is_zero ( ) ) {
2020-04-03 01:38:35 -03:00
// if only A or B have been stored, spray on
spray ( true ) ;
2018-09-29 06:25:31 -03:00
}
break ;
case AUTO :
case MANUAL_REGAIN :
// A and B have been defined, move vehicle to destination A or B
Vector3f next_dest ;
2019-04-11 01:34:30 -03:00
bool terr_alt ;
2020-02-22 09:58:42 -04:00
if ( calculate_next_dest ( ab_dest , stage = = AUTO , next_dest , terr_alt ) ) {
2018-09-29 06:25:31 -03:00
wp_nav - > wp_and_spline_init ( ) ;
2019-04-11 01:34:30 -03:00
if ( wp_nav - > set_wp_destination ( next_dest , terr_alt ) ) {
2018-09-29 06:25:31 -03:00
stage = AUTO ;
2020-04-03 01:48:23 -03:00
auto_stage = AutoState : : AB_MOVING ;
ab_dest_stored = ab_dest ;
2020-02-02 09:07:42 -04:00
// spray on while moving to A or B
2020-04-03 01:38:35 -03:00
spray ( true ) ;
2018-09-29 06:25:31 -03:00
reach_wp_time_ms = 0 ;
2020-04-07 12:23:27 -03:00
if ( is_auto = = false | | line_num = = ZIGZAG_LINE_INFINITY ) {
2020-04-03 04:51:59 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " ZigZag: moving to %s " , ( ab_dest = = Destination : : A ) ? " A " : " B " ) ;
} else {
line_count + + ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " ZigZag: moving to %s (line %d/%d) " , ( ab_dest = = Destination : : A ) ? " A " : " B " , line_count , line_num ) ;
}
2018-09-29 06:25:31 -03:00
}
}
break ;
}
}
2020-04-03 01:48:23 -03:00
void ModeZigZag : : move_to_side ( )
{
if ( ! dest_A . is_zero ( ) & & ! dest_B . is_zero ( ) & & ! is_zero ( ( dest_B - dest_A ) . length_squared ( ) ) ) {
Vector3f next_dest ;
bool terr_alt ;
if ( calculate_side_dest ( next_dest , terr_alt ) ) {
wp_nav - > wp_and_spline_init ( ) ;
if ( wp_nav - > set_wp_destination ( next_dest , terr_alt ) ) {
stage = AUTO ;
auto_stage = AutoState : : SIDEWAYS ;
2020-04-07 12:23:27 -03:00
current_dest = next_dest ;
current_terr_alt = terr_alt ;
2020-04-03 01:48:23 -03:00
reach_wp_time_ms = 0 ;
char const * dir [ ] = { " forward " , " right " , " backward " , " left " } ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " ZigZag: moving to %s " , dir [ ( uint8_t ) zigzag_direction ] ) ;
}
}
}
}
2018-09-29 06:25:31 -03:00
// return manual control to the pilot
2019-05-09 23:18:49 -03:00
void ModeZigZag : : return_to_manual_control ( bool maintain_target )
2018-09-29 06:25:31 -03:00
{
if ( stage = = AUTO ) {
stage = MANUAL_REGAIN ;
2020-04-03 01:38:35 -03:00
spray ( false ) ;
2018-09-29 06:25:31 -03:00
loiter_nav - > clear_pilot_desired_acceleration ( ) ;
2019-08-21 23:47:43 -03:00
if ( maintain_target ) {
2019-11-11 07:33:14 -04:00
const Vector3f & wp_dest = wp_nav - > get_wp_destination ( ) ;
2021-06-21 04:22:48 -03:00
loiter_nav - > init_target ( wp_dest . xy ( ) ) ;
2019-08-21 23:47:43 -03:00
if ( wp_nav - > origin_and_destination_are_terrain_alt ( ) ) {
copter . surface_tracking . set_target_alt_cm ( wp_dest . z ) ;
}
} else {
loiter_nav - > init_target ( ) ;
2019-04-11 01:34:30 -03:00
}
2020-04-03 04:51:59 -03:00
is_auto = false ;
2018-09-29 06:25:31 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " ZigZag: manual control " ) ;
}
2018-09-07 01:23:33 -03:00
}
2018-09-29 06:25:31 -03:00
// fly the vehicle to closest point on line perpendicular to dest_A or dest_B
2019-05-09 23:18:49 -03:00
void ModeZigZag : : auto_control ( )
2018-09-07 01:23:33 -03:00
{
// process pilot's yaw input
float target_yaw_rate = 0 ;
if ( ! copter . failsafe . radio ) {
// get pilot's desired yaw rate
2021-09-17 02:54:19 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > norm_input_dz ( ) ) ;
2018-09-07 01:23:33 -03:00
}
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2018-09-07 01:23:33 -03:00
2018-09-29 06:25:31 -03:00
// run waypoint controller
2019-04-11 01:34:30 -03:00
const bool wpnav_ok = wp_nav - > update_wpnav ( ) ;
2018-09-07 01:23:33 -03:00
2021-05-19 11:07:38 -03:00
// WP_Nav has set the vertical position control targets
// run the vertical position controller and set output throttle
2018-09-07 01:23:33 -03:00
pos_control - > update_z_controller ( ) ;
// call attitude controller
// roll & pitch from waypoint controller, yaw rate from pilot
2019-04-11 01:34:30 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
// if wpnav failed (because of lack of terrain data) switch back to pilot control for next iteration
if ( ! wpnav_ok ) {
return_to_manual_control ( false ) ;
}
2018-09-07 01:23:33 -03:00
}
// manual_control - process manual control
2019-05-09 23:18:49 -03:00
void ModeZigZag : : manual_control ( )
2018-09-07 01:23:33 -03:00
{
float target_yaw_rate = 0.0f ;
float target_climb_rate = 0.0f ;
// process pilot inputs unless we are in radio failsafe
if ( ! copter . failsafe . radio ) {
float target_roll , target_pitch ;
// apply SIMPLE mode transform to pilot inputs
update_simple_mode ( ) ;
// convert pilot input to lean angles
2021-09-06 06:44:18 -03:00
get_pilot_desired_lean_angles ( target_roll , target_pitch , loiter_nav - > get_angle_max_cd ( ) , attitude_control - > get_althold_lean_angle_max_cd ( ) ) ;
2018-09-07 01:23:33 -03:00
// process pilot's roll and pitch input
2021-05-11 01:42:02 -03:00
loiter_nav - > set_pilot_desired_acceleration ( target_roll , target_pitch ) ;
2018-09-07 01:23:33 -03:00
// get pilot's desired yaw rate
2021-09-17 02:54:19 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > norm_input_dz ( ) ) ;
2018-09-07 01:23:33 -03:00
// get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate ( channel_throttle - > get_control_in ( ) ) ;
// make sure the climb rate is in the given range, prevent floating point errors
target_climb_rate = constrain_float ( target_climb_rate , - get_pilot_speed_dn ( ) , g . pilot_speed_up ) ;
} else {
// clear out pilot desired acceleration in case radio failsafe event occurs and we
// do not switch to RTL for some reason
loiter_nav - > clear_pilot_desired_acceleration ( ) ;
}
2020-02-05 22:33:15 -04:00
// relax loiter target if we might be landed
if ( copter . ap . land_complete_maybe ) {
loiter_nav - > soften_for_landing ( ) ;
}
// Loiter State Machine Determination
AltHoldModeState althold_state = get_alt_hold_state ( target_climb_rate ) ;
// althold state machine
switch ( althold_state ) {
case AltHold_MotorStopped :
attitude_control - > reset_rate_controller_I_terms ( ) ;
2021-05-24 10:42:19 -03:00
attitude_control - > reset_yaw_target_and_rate ( ) ;
2021-05-19 11:07:38 -03:00
pos_control - > relax_z_controller ( 0.0f ) ; // forces throttle output to decay to zero
2020-02-05 22:33:15 -04:00
loiter_nav - > init_target ( ) ;
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( loiter_nav - > get_roll ( ) , loiter_nav - > get_pitch ( ) , target_yaw_rate ) ;
break ;
case AltHold_Takeoff :
// initiate take-off
if ( ! takeoff . running ( ) ) {
takeoff . start ( constrain_float ( g . pilot_takeoff_alt , 0.0f , 1000.0f ) ) ;
}
2018-09-29 06:25:31 -03:00
2020-02-05 22:33:15 -04:00
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate ( target_climb_rate ) ;
2018-09-07 01:23:33 -03:00
2020-02-05 22:33:15 -04:00
// run loiter controller
loiter_nav - > update ( ) ;
2018-09-07 01:23:33 -03:00
2020-02-05 22:33:15 -04:00
// call attitude controller
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( loiter_nav - > get_roll ( ) , loiter_nav - > get_pitch ( ) , target_yaw_rate ) ;
2018-09-07 01:23:33 -03:00
2021-05-19 11:07:38 -03:00
// set position controller targets adjusted for pilot input
2021-05-13 02:40:05 -03:00
takeoff . do_pilot_takeoff ( target_climb_rate ) ;
2020-02-05 22:33:15 -04:00
break ;
2018-09-07 01:23:33 -03:00
2020-02-05 22:33:15 -04:00
case AltHold_Landed_Ground_Idle :
2021-05-24 10:42:19 -03:00
attitude_control - > reset_yaw_target_and_rate ( ) ;
2020-02-05 22:33:15 -04:00
FALLTHROUGH ;
case AltHold_Landed_Pre_Takeoff :
2020-12-20 17:40:58 -04:00
attitude_control - > reset_rate_controller_I_terms_smoothly ( ) ;
2020-02-05 22:33:15 -04:00
loiter_nav - > init_target ( ) ;
2021-05-24 11:06:49 -03:00
attitude_control - > input_thrust_vector_rate_heading ( loiter_nav - > get_thrust_vector ( ) , target_yaw_rate ) ;
2021-05-19 11:07:38 -03:00
pos_control - > relax_z_controller ( 0.0f ) ; // forces throttle output to decay to zero
2020-02-05 22:33:15 -04:00
break ;
case AltHold_Flying :
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
// run loiter controller
loiter_nav - > update ( ) ;
// call attitude controller
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( loiter_nav - > get_roll ( ) , loiter_nav - > get_pitch ( ) , target_yaw_rate ) ;
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate ( target_climb_rate ) ;
2021-08-31 01:17:59 -03:00
// update the vertical offset based on the surface measurement
copter . surface_tracking . update_surface_offset ( ) ;
// Send the commanded climb rate to the position controller
pos_control - > set_pos_target_z_from_climb_rate_cm ( target_climb_rate ) ;
2020-02-05 22:33:15 -04:00
break ;
}
2021-05-13 02:40:05 -03:00
2021-05-19 11:07:38 -03:00
// run the vertical position controller and set output throttle
2021-05-13 02:40:05 -03:00
pos_control - > update_z_controller ( ) ;
2018-09-07 01:23:33 -03:00
}
2018-09-29 06:25:31 -03:00
// return true if vehicle is within a small area around the destination
2019-05-09 23:18:49 -03:00
bool ModeZigZag : : reached_destination ( )
2018-09-07 01:23:33 -03:00
{
2018-09-29 06:25:31 -03:00
// check if wp_nav believes it has reached the destination
if ( ! wp_nav - > reached_wp_destination ( ) ) {
2018-09-07 01:23:33 -03:00
return false ;
}
2018-09-29 06:25:31 -03:00
// check distance to destination
if ( wp_nav - > get_wp_distance_to_destination ( ) > ZIGZAG_WP_RADIUS_CM ) {
2018-09-07 01:23:33 -03:00
return false ;
}
2018-09-29 06:25:31 -03:00
2020-04-02 05:25:39 -03:00
// wait at time which is set in zigzag_wp_delay
2018-09-29 06:25:31 -03:00
uint32_t now = AP_HAL : : millis ( ) ;
if ( reach_wp_time_ms = = 0 ) {
reach_wp_time_ms = now ;
2018-09-07 01:23:33 -03:00
}
2021-11-03 23:55:53 -03:00
return ( ( now - reach_wp_time_ms ) > = ( uint16_t ) constrain_int16 ( _wp_delay , 0 , 127 ) * 1000 ) ;
2018-09-07 01:23:33 -03:00
}
2018-09-29 06:25:31 -03:00
// calculate next destination according to vector A-B and current position
2019-04-11 01:34:30 -03:00
// use_wpnav_alt should be true if waypoint controller's altitude target should be used, false for position control or current altitude target
// terrain_alt is returned as true if the next_dest should be considered a terrain alt
2020-02-22 09:58:42 -04:00
bool ModeZigZag : : calculate_next_dest ( Destination ab_dest , bool use_wpnav_alt , Vector3f & next_dest , bool & terrain_alt ) const
2018-09-07 01:23:33 -03:00
{
2020-02-22 09:58:42 -04:00
// define start_pos as either destination A or B
Vector2f start_pos = ( ab_dest = = Destination : : A ) ? dest_A : dest_B ;
2018-09-07 01:23:33 -03:00
2018-09-29 06:25:31 -03:00
// calculate vector from A to B
Vector2f AB_diff = dest_B - dest_A ;
2018-09-07 01:23:33 -03:00
2018-09-29 06:25:31 -03:00
// check distance between A and B
2020-04-03 01:48:23 -03:00
if ( is_zero ( AB_diff . length_squared ( ) ) ) {
2018-09-07 01:23:33 -03:00
return false ;
}
2018-09-29 06:25:31 -03:00
// get distance from vehicle to start_pos
2021-10-20 05:29:57 -03:00
const Vector2f curr_pos2d { inertial_nav . get_position_xy_cm ( ) } ;
2018-09-29 06:25:31 -03:00
Vector2f veh_to_start_pos = curr_pos2d - start_pos ;
// lengthen AB_diff so that it is at least as long as vehicle is from start point
// we need to ensure that the lines perpendicular to AB are long enough to reach the vehicle
float scalar = 1.0f ;
if ( veh_to_start_pos . length_squared ( ) > AB_diff . length_squared ( ) ) {
scalar = veh_to_start_pos . length ( ) / AB_diff . length ( ) ;
2018-09-07 01:23:33 -03:00
}
2018-09-29 06:25:31 -03:00
// create a line perpendicular to AB but originating at start_pos
Vector2f perp1 = start_pos + Vector2f ( - AB_diff [ 1 ] * scalar , AB_diff [ 0 ] * scalar ) ;
Vector2f perp2 = start_pos + Vector2f ( AB_diff [ 1 ] * scalar , - AB_diff [ 0 ] * scalar ) ;
// find the closest point on the perpendicular line
const Vector2f closest2d = Vector2f : : closest_point ( curr_pos2d , perp1 , perp2 ) ;
next_dest . x = closest2d . x ;
next_dest . y = closest2d . y ;
2019-04-11 01:34:30 -03:00
if ( use_wpnav_alt ) {
// get altitude target from waypoint controller
terrain_alt = wp_nav - > origin_and_destination_are_terrain_alt ( ) ;
next_dest . z = wp_nav - > get_wp_destination ( ) . z ;
} else {
// if we have a downward facing range finder then use terrain altitude targets
2019-12-12 07:05:00 -04:00
terrain_alt = copter . rangefinder_alt_ok ( ) & & wp_nav - > rangefinder_used_and_healthy ( ) ;
2019-04-11 01:34:30 -03:00
if ( terrain_alt ) {
2019-06-11 00:13:24 -03:00
if ( ! copter . surface_tracking . get_target_alt_cm ( next_dest . z ) ) {
2019-04-11 01:34:30 -03:00
next_dest . z = copter . rangefinder_state . alt_cm_filt . get ( ) ;
}
} else {
2021-10-20 05:29:57 -03:00
next_dest . z = pos_control - > is_active_z ( ) ? pos_control - > get_pos_target_z_cm ( ) : inertial_nav . get_position_z_up_cm ( ) ;
2019-04-11 01:34:30 -03:00
}
}
2018-09-29 06:25:31 -03:00
return true ;
2018-09-07 01:23:33 -03:00
}
2018-09-29 06:25:31 -03:00
2020-04-03 01:48:23 -03:00
// calculate side destination according to vertical vector A-B and current position
// terrain_alt is returned as true if the next_dest should be considered a terrain alt
bool ModeZigZag : : calculate_side_dest ( Vector3f & next_dest , bool & terrain_alt ) const
{
// calculate vector from A to B
Vector2f AB_diff = dest_B - dest_A ;
// calculate a vertical right or left vector for AB from the current yaw direction
Vector2f AB_side ;
if ( zigzag_direction = = Direction : : RIGHT | | zigzag_direction = = Direction : : LEFT ) {
float yaw_ab_sign = ( - ahrs . sin_yaw ( ) * AB_diff [ 1 ] ) + ( ahrs . cos_yaw ( ) * - AB_diff [ 0 ] ) ;
if ( is_positive ( yaw_ab_sign * ( zigzag_direction = = Direction : : RIGHT ? 1 : - 1 ) ) ) {
AB_side = Vector2f ( AB_diff [ 1 ] , - AB_diff [ 0 ] ) ;
} else {
AB_side = Vector2f ( - AB_diff [ 1 ] , AB_diff [ 0 ] ) ;
}
} else {
float yaw_ab_sign = ( ahrs . cos_yaw ( ) * AB_diff [ 1 ] ) + ( ahrs . sin_yaw ( ) * - AB_diff [ 0 ] ) ;
if ( is_positive ( yaw_ab_sign * ( zigzag_direction = = Direction : : FORWARD ? 1 : - 1 ) ) ) {
AB_side = Vector2f ( AB_diff [ 1 ] , - AB_diff [ 0 ] ) ;
} else {
AB_side = Vector2f ( - AB_diff [ 1 ] , AB_diff [ 0 ] ) ;
}
}
// check distance the vertical vector between A and B
if ( is_zero ( AB_side . length_squared ( ) ) ) {
return false ;
}
// adjust AB_side length to zigzag_side_dist
2020-05-11 23:17:21 -03:00
float scalar = constrain_float ( _side_dist , 0.1f , 100.0f ) * 100 / safe_sqrt ( AB_side . length_squared ( ) ) ;
2020-04-03 01:48:23 -03:00
// get distance from vehicle to start_pos
2021-10-20 05:29:57 -03:00
const Vector2f curr_pos2d { inertial_nav . get_position_xy_cm ( ) } ;
2020-04-03 01:48:23 -03:00
next_dest . x = curr_pos2d . x + ( AB_side . x * scalar ) ;
next_dest . y = curr_pos2d . y + ( AB_side . y * scalar ) ;
// if we have a downward facing range finder then use terrain altitude targets
terrain_alt = copter . rangefinder_alt_ok ( ) & & wp_nav - > rangefinder_used_and_healthy ( ) ;
if ( terrain_alt ) {
if ( ! copter . surface_tracking . get_target_alt_cm ( next_dest . z ) ) {
next_dest . z = copter . rangefinder_state . alt_cm_filt . get ( ) ;
}
} else {
2021-10-20 05:29:57 -03:00
next_dest . z = pos_control - > is_active_z ( ) ? pos_control - > get_pos_target_z_cm ( ) : inertial_nav . get_position_z_up_cm ( ) ;
2020-04-03 01:48:23 -03:00
}
return true ;
}
// run zigzag auto feature which is automate both AB and sideways
void ModeZigZag : : run_auto ( )
{
2020-05-11 23:17:21 -03:00
// exit immediately if we are disabled
if ( ! _auto_enabled ) {
return ;
}
2020-04-07 12:23:27 -03:00
// make sure both A and B point are registered and not when moving to A or B
if ( stage ! = MANUAL_REGAIN ) {
return ;
}
2020-04-03 01:48:23 -03:00
is_auto = true ;
2020-04-07 12:23:27 -03:00
// resume if zigzag auto is suspended
if ( is_suspended & & line_count < = line_num ) {
// resume the stage when it was suspended
if ( auto_stage = = AutoState : : AB_MOVING ) {
line_count - - ;
save_or_move_to_destination ( ab_dest_stored ) ;
} else if ( auto_stage = = AutoState : : SIDEWAYS ) {
wp_nav - > wp_and_spline_init ( ) ;
if ( wp_nav - > set_wp_destination ( current_dest , current_terr_alt ) ) {
stage = AUTO ;
reach_wp_time_ms = 0 ;
char const * dir [ ] = { " forward " , " right " , " backward " , " left " } ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " ZigZag: moving to %s " , dir [ ( uint8_t ) zigzag_direction ] ) ;
}
}
} else {
move_to_side ( ) ;
}
}
// suspend zigzag auto
void ModeZigZag : : suspend_auto ( )
{
2020-05-11 23:17:21 -03:00
// exit immediately if we are disabled
if ( ! _auto_enabled ) {
return ;
}
2020-04-07 12:23:27 -03:00
if ( auto_stage ! = AutoState : : MANUAL ) {
is_suspended = true ;
return_to_manual_control ( true ) ;
}
}
// initialize zigzag auto
void ModeZigZag : : init_auto ( )
{
is_auto = false ;
auto_stage = AutoState : : MANUAL ;
line_count = 0 ;
is_suspended = false ;
2020-04-03 01:48:23 -03:00
}
2020-04-03 01:38:35 -03:00
// spray on / off
void ModeZigZag : : spray ( bool b )
{
2022-11-01 00:11:31 -03:00
# if HAL_SPRAYER_ENABLED
2020-05-11 23:17:21 -03:00
if ( _spray_enabled ) {
2020-04-03 01:38:35 -03:00
copter . sprayer . run ( b ) ;
}
# endif
}
2021-05-16 02:21:47 -03:00
uint32_t ModeZigZag : : wp_distance ( ) const
{
if ( is_auto ) {
return wp_nav - > get_wp_distance_to_destination ( ) ;
} else {
return 0 ;
}
}
int32_t ModeZigZag : : wp_bearing ( ) const
{
if ( is_auto ) {
return wp_nav - > get_wp_bearing_to_destination ( ) ;
} else {
return 0 ;
}
}
float ModeZigZag : : crosstrack_error ( ) const
{
if ( is_auto ) {
return wp_nav - > crosstrack_error ( ) ;
} else {
return 0 ;
}
}
2018-09-07 01:23:33 -03:00
# endif // MODE_ZIGZAG_ENABLED == ENABLED