2017-07-18 23:17:45 -03:00
# include "Rover.h"
bool ModeGuided : : _enter ( )
{
2021-12-01 22:34:51 -04:00
// initialise submode to stop or loiter
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
start_stop ( ) ;
}
} else {
start_stop ( ) ;
2019-04-29 03:31:45 -03:00
}
2022-01-05 20:01:49 -04:00
// initialise waypoint navigation library
g2 . wp_nav . init ( ) ;
2017-12-05 21:41:28 -04:00
2021-03-03 00:51:46 -04:00
send_notification = false ;
2017-08-03 03:19:57 -03:00
2017-07-18 23:17:45 -03:00
return true ;
}
void ModeGuided : : update ( )
{
2017-08-03 05:14:16 -03:00
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2017-08-03 05:14:16 -03:00
{
2018-02-05 02:39:48 -04:00
// check if we've reached the destination
2019-04-29 03:31:45 -03:00
if ( ! g2 . wp_nav . reached_destination ( ) ) {
// update navigation controller
navigate_to_waypoint ( ) ;
2017-08-03 05:14:16 -03:00
} else {
2019-04-29 03:31:45 -03:00
// send notification
2021-03-03 00:51:46 -04:00
if ( send_notification ) {
send_notification = false ;
2019-04-29 03:31:45 -03:00
rover . gcs ( ) . send_mission_item_reached_message ( 0 ) ;
}
2019-01-10 06:46:43 -04:00
// we have reached the destination so stay here
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
stop_vehicle ( ) ;
}
2018-12-03 15:25:52 -04:00
} else {
stop_vehicle ( ) ;
}
2019-04-29 03:31:45 -03:00
// update distance to destination
_distance_to_destination = rover . current_loc . get_distance ( g2 . wp_nav . get_destination ( ) ) ;
2017-08-03 05:14:16 -03:00
}
break ;
}
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
2017-08-03 05:14:16 -03:00
{
// stop vehicle if target not updated within 3 seconds
if ( have_attitude_target & & ( millis ( ) - _des_att_time_ms ) > 3000 ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " target not received last 3secs, stopping " ) ;
have_attitude_target = false ;
}
if ( have_attitude_target ) {
// run steering and throttle controllers
2018-09-10 04:25:15 -03:00
calc_steering_to_heading ( _desired_yaw_cd ) ;
2019-05-04 00:09:24 -03:00
calc_throttle ( calc_speed_nudge ( _desired_speed , is_negative ( _desired_speed ) ) , true ) ;
2017-07-18 23:17:45 -03:00
} else {
2019-01-10 06:46:43 -04:00
// we have reached the destination so stay here
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
stop_vehicle ( ) ;
}
2018-12-03 15:25:52 -04:00
} else {
stop_vehicle ( ) ;
}
2017-07-18 23:17:45 -03:00
}
break ;
2017-08-03 05:14:16 -03:00
}
2017-07-18 23:17:45 -03:00
2023-09-21 10:44:53 -03:00
case SubMode : : TurnRateAndSpeed :
2017-08-03 05:14:16 -03:00
{
// stop vehicle if target not updated within 3 seconds
if ( have_attitude_target & & ( millis ( ) - _des_att_time_ms ) > 3000 ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " target not received last 3secs, stopping " ) ;
have_attitude_target = false ;
}
if ( have_attitude_target ) {
// run steering and throttle controllers
2024-05-02 16:11:10 -03:00
float steering_out = attitude_control . get_steering_out_rate ( radians ( _desired_yaw_rate_cds * 0.01f ) ,
2018-04-09 09:12:07 -03:00
g2 . motors . limit . steer_left ,
2018-05-21 22:05:20 -03:00
g2 . motors . limit . steer_right ,
rover . G_Dt ) ;
2019-04-20 20:02:51 -03:00
set_steering ( steering_out * 4500.0f ) ;
2019-05-04 00:09:24 -03:00
calc_throttle ( calc_speed_nudge ( _desired_speed , is_negative ( _desired_speed ) ) , true ) ;
2017-08-03 05:14:16 -03:00
} else {
2019-01-10 06:46:43 -04:00
// we have reached the destination so stay here
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
stop_vehicle ( ) ;
}
2018-12-03 15:25:52 -04:00
} else {
stop_vehicle ( ) ;
}
2017-08-03 05:14:16 -03:00
}
2017-07-18 23:17:45 -03:00
break ;
2017-08-03 05:14:16 -03:00
}
2017-07-18 23:17:45 -03:00
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2018-12-03 15:25:52 -04:00
{
rover . mode_loiter . update ( ) ;
break ;
}
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
2020-06-15 04:29:00 -03:00
{
// handle timeout
if ( _have_strthr & & ( AP_HAL : : millis ( ) - _strthr_time_ms ) > 3000 ) {
_have_strthr = false ;
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " target not received last 3secs, stopping " ) ;
}
if ( _have_strthr ) {
// pass latest steering and throttle directly to motors library
g2 . motors . set_steering ( _strthr_steering * 4500.0f , false ) ;
g2 . motors . set_throttle ( _strthr_throttle * 100.0f ) ;
} else {
// loiter or stop vehicle
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
stop_vehicle ( ) ;
}
} else {
stop_vehicle ( ) ;
}
}
break ;
}
2023-09-21 10:44:53 -03:00
case SubMode : : Stop :
2021-12-01 22:34:51 -04:00
stop_vehicle ( ) ;
break ;
2017-07-18 23:17:45 -03:00
default :
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Unknown GUIDED mode " ) ;
break ;
}
}
2021-11-19 23:05:23 -04:00
// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message)
float ModeGuided : : wp_bearing ( ) const
{
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2021-11-19 23:05:23 -04:00
return g2 . wp_nav . wp_bearing_cd ( ) * 0.01f ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
2021-11-19 23:05:23 -04:00
return 0.0f ;
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2021-11-19 23:05:23 -04:00
return rover . mode_loiter . wp_bearing ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2021-11-19 23:05:23 -04:00
return 0.0f ;
}
// we should never reach here but just in case, return 0
return 0.0f ;
}
float ModeGuided : : nav_bearing ( ) const
{
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2021-11-19 23:05:23 -04:00
return g2 . wp_nav . nav_bearing_cd ( ) * 0.01f ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
2021-11-19 23:05:23 -04:00
return 0.0f ;
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2021-11-19 23:05:23 -04:00
return rover . mode_loiter . nav_bearing ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2021-11-19 23:05:23 -04:00
return 0.0f ;
}
// we should never reach here but just in case, return 0
return 0.0f ;
}
float ModeGuided : : crosstrack_error ( ) const
{
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2021-11-19 23:05:23 -04:00
return g2 . wp_nav . crosstrack_error ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
2021-11-19 23:05:23 -04:00
return 0.0f ;
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2021-11-19 23:05:23 -04:00
return rover . mode_loiter . crosstrack_error ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2021-11-19 23:05:23 -04:00
return 0.0f ;
}
// we should never reach here but just in case, return 0
return 0.0f ;
}
float ModeGuided : : get_desired_lat_accel ( ) const
{
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2021-11-19 23:05:23 -04:00
return g2 . wp_nav . get_lat_accel ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
2021-11-19 23:05:23 -04:00
return 0.0f ;
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2021-11-19 23:05:23 -04:00
return rover . mode_loiter . get_desired_lat_accel ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2021-11-19 23:05:23 -04:00
return 0.0f ;
}
// we should never reach here but just in case, return 0
return 0.0f ;
}
2017-08-03 05:14:16 -03:00
// return distance (in meters) to destination
float ModeGuided : : get_distance_to_destination ( ) const
2017-07-18 23:17:45 -03:00
{
2019-04-29 03:31:45 -03:00
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2019-04-29 03:31:45 -03:00
return _distance_to_destination ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
2017-08-03 05:14:16 -03:00
return 0.0f ;
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2019-06-05 01:05:41 -03:00
return rover . mode_loiter . get_distance_to_destination ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2020-06-15 04:29:00 -03:00
return 0.0f ;
2017-07-18 23:17:45 -03:00
}
2019-04-29 03:31:45 -03:00
// we should never reach here but just in case, return 0
return 0.0f ;
2017-08-03 05:14:16 -03:00
}
2019-03-08 01:41:50 -04:00
// return true if vehicle has reached or even passed destination
2019-03-15 01:26:01 -03:00
bool ModeGuided : : reached_destination ( ) const
2019-03-08 01:41:50 -04:00
{
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2022-01-02 23:51:29 -04:00
return g2 . wp_nav . reached_destination ( ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
case SubMode : : Loiter :
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2019-03-08 01:41:50 -04:00
return true ;
}
// we should never reach here but just in case, return true is the safer option
return true ;
}
2019-11-04 04:31:13 -04:00
// set desired speed in m/s
bool ModeGuided : : set_desired_speed ( float speed )
{
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2022-01-05 20:43:58 -04:00
return g2 . wp_nav . set_speed_max ( speed ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
2019-11-04 04:31:13 -04:00
// speed is set from mavlink message
return false ;
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2019-11-04 04:31:13 -04:00
return rover . mode_loiter . set_desired_speed ( speed ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2020-06-15 04:29:00 -03:00
// no speed control
return false ;
2019-11-04 04:31:13 -04:00
}
return false ;
}
2019-05-17 03:55:31 -03:00
// get desired location
bool ModeGuided : : get_desired_location ( Location & destination ) const
{
switch ( _guided_mode ) {
2023-09-21 10:44:53 -03:00
case SubMode : : WP :
2019-05-17 03:55:31 -03:00
if ( g2 . wp_nav . is_destination_valid ( ) ) {
2019-05-10 02:59:52 -03:00
destination = g2 . wp_nav . get_oa_destination ( ) ;
2019-05-17 03:55:31 -03:00
return true ;
}
return false ;
2023-09-21 10:44:53 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : TurnRateAndSpeed :
2019-05-17 03:55:31 -03:00
// not supported in these submodes
return false ;
2023-09-21 10:44:53 -03:00
case SubMode : : Loiter :
2019-05-17 03:55:31 -03:00
// get destination from loiter
return rover . mode_loiter . get_desired_location ( destination ) ;
2023-09-21 10:44:53 -03:00
case SubMode : : SteeringAndThrottle :
case SubMode : : Stop :
2020-06-15 04:29:00 -03:00
// no desired location in this submode
break ;
2019-05-17 03:55:31 -03:00
}
// should never get here but just in case
return false ;
}
2017-08-03 05:14:16 -03:00
// set desired location
2021-11-18 23:38:12 -04:00
bool ModeGuided : : set_desired_location ( const Location & destination , Location next_destination )
2017-08-03 05:14:16 -03:00
{
2021-11-19 23:05:23 -04:00
if ( use_scurves_for_navigation ( ) ) {
// use scurves for navigation
if ( ! g2 . wp_nav . set_desired_location ( destination , next_destination ) ) {
return false ;
}
} else {
// use position controller input shaping for navigation
// this does not support object avoidance but does allow faster updates of the target
if ( ! g2 . wp_nav . set_desired_location_expect_fast_update ( destination ) ) {
return false ;
}
2019-04-29 03:31:45 -03:00
}
2021-11-19 23:05:23 -04:00
// handle guided specific initialisation and logging
2023-09-21 10:44:53 -03:00
_guided_mode = SubMode : : WP ;
2021-11-19 23:05:23 -04:00
send_notification = true ;
2024-02-07 16:42:28 -04:00
# if HAL_LOGGING_ENABLED
2023-09-21 10:44:53 -03:00
rover . Log_Write_GuidedTarget ( ( uint8_t ) _guided_mode , Vector3f ( destination . lat , destination . lng , 0 ) , Vector3f ( g2 . wp_nav . get_speed_max ( ) , 0.0f , 0.0f ) ) ;
2024-02-07 16:42:28 -04:00
# endif
2021-11-19 23:05:23 -04:00
return true ;
2017-08-03 05:14:16 -03:00
}
// set desired attitude
void ModeGuided : : set_desired_heading_and_speed ( float yaw_angle_cd , float target_speed )
{
2019-11-04 04:31:13 -04:00
// initialisation and logging
2023-09-21 10:44:53 -03:00
_guided_mode = SubMode : : HeadingAndSpeed ;
2017-08-03 05:14:16 -03:00
_des_att_time_ms = AP_HAL : : millis ( ) ;
// record targets
_desired_yaw_cd = yaw_angle_cd ;
_desired_speed = target_speed ;
have_attitude_target = true ;
2024-02-07 16:42:28 -04:00
# if HAL_LOGGING_ENABLED
2017-08-03 05:14:16 -03:00
// log new target
2023-09-21 10:44:53 -03:00
rover . Log_Write_GuidedTarget ( ( uint8_t ) _guided_mode , Vector3f ( _desired_yaw_cd , 0.0f , 0.0f ) , Vector3f ( _desired_speed , 0.0f , 0.0f ) ) ;
2024-02-07 16:42:28 -04:00
# endif
2017-08-03 05:14:16 -03:00
}
void ModeGuided : : set_desired_heading_delta_and_speed ( float yaw_delta_cd , float target_speed )
{
// handle initialisation
2023-09-21 10:44:53 -03:00
if ( _guided_mode ! = SubMode : : HeadingAndSpeed ) {
_guided_mode = SubMode : : HeadingAndSpeed ;
2017-08-03 05:14:16 -03:00
_desired_yaw_cd = ahrs . yaw_sensor ;
}
2017-08-03 06:41:47 -03:00
set_desired_heading_and_speed ( wrap_180_cd ( _desired_yaw_cd + yaw_delta_cd ) , target_speed ) ;
2017-08-03 05:14:16 -03:00
}
// set desired velocity
void ModeGuided : : set_desired_turn_rate_and_speed ( float turn_rate_cds , float target_speed )
{
// handle initialisation
2023-09-21 10:44:53 -03:00
_guided_mode = SubMode : : TurnRateAndSpeed ;
2017-08-03 05:14:16 -03:00
_des_att_time_ms = AP_HAL : : millis ( ) ;
// record targets
_desired_yaw_rate_cds = turn_rate_cds ;
_desired_speed = target_speed ;
have_attitude_target = true ;
2024-02-07 16:42:28 -04:00
# if HAL_LOGGING_ENABLED
2017-08-03 05:14:16 -03:00
// log new target
2023-09-21 10:44:53 -03:00
rover . Log_Write_GuidedTarget ( ( uint8_t ) _guided_mode , Vector3f ( _desired_yaw_rate_cds , 0.0f , 0.0f ) , Vector3f ( _desired_speed , 0.0f , 0.0f ) ) ;
2024-02-07 16:42:28 -04:00
# endif
2017-07-18 23:17:45 -03:00
}
2018-12-03 15:25:52 -04:00
2020-06-15 04:29:00 -03:00
// set steering and throttle (both in the range -1 to +1)
void ModeGuided : : set_steering_and_throttle ( float steering , float throttle )
{
2023-09-21 10:44:53 -03:00
_guided_mode = SubMode : : SteeringAndThrottle ;
2020-06-15 04:29:00 -03:00
_strthr_time_ms = AP_HAL : : millis ( ) ;
_strthr_steering = constrain_float ( steering , - 1.0f , 1.0f ) ;
_strthr_throttle = constrain_float ( throttle , - 1.0f , 1.0f ) ;
_have_strthr = true ;
}
2018-12-03 15:25:52 -04:00
bool ModeGuided : : start_loiter ( )
{
if ( rover . mode_loiter . enter ( ) ) {
2023-09-21 10:44:53 -03:00
_guided_mode = SubMode : : Loiter ;
2018-12-03 15:25:52 -04:00
return true ;
}
return false ;
}
2019-03-08 04:53:22 -04:00
2021-12-01 22:34:51 -04:00
// start stopping vehicle as quickly as possible
void ModeGuided : : start_stop ( )
{
2023-09-21 10:44:53 -03:00
_guided_mode = SubMode : : Stop ;
2021-12-01 22:34:51 -04:00
}
2019-03-08 04:53:22 -04:00
// set guided timeout and movement limits
void ModeGuided : : limit_set ( uint32_t timeout_ms , float horiz_max )
{
limit . timeout_ms = timeout_ms ;
limit . horiz_max = horiz_max ;
}
// clear/turn off guided limits
void ModeGuided : : limit_clear ( )
{
limit . timeout_ms = 0 ;
limit . horiz_max = 0.0f ;
}
// initialise guided start time and location as reference for limit checking
// only called from AUTO mode's start_guided method
void ModeGuided : : limit_init_time_and_location ( )
{
2019-03-15 03:00:31 -03:00
limit . start_time_ms = AP_HAL : : millis ( ) ;
2019-03-08 04:53:22 -04:00
limit . start_loc = rover . current_loc ;
}
// returns true if guided mode has breached a limit
2019-03-15 01:22:36 -03:00
bool ModeGuided : : limit_breached ( ) const
2019-03-08 04:53:22 -04:00
{
// check if we have passed the timeout
2019-03-15 03:00:31 -03:00
if ( ( limit . timeout_ms > 0 ) & & ( millis ( ) - limit . start_time_ms > = limit . timeout_ms ) ) {
2019-03-08 04:53:22 -04:00
return true ;
}
// check if we have gone beyond horizontal limit
2019-03-15 01:22:36 -03:00
if ( is_positive ( limit . horiz_max ) ) {
2019-03-08 04:53:22 -04:00
return ( rover . current_loc . get_distance ( limit . start_loc ) > limit . horiz_max ) ;
}
// if we got this far we must be within limits
return false ;
}
2021-11-19 23:05:23 -04:00
// returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping
// scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping)
bool ModeGuided : : use_scurves_for_navigation ( ) const
{
2024-05-03 07:02:37 -03:00
return ( ( g2 . guided_options . get ( ) & uint32_t ( Options : : SCurvesUsedForNavigation ) ) ! = 0 ) ;
2021-11-19 23:05:23 -04:00
}