// guided_set_destination - sets guided mode's target destination // Returns true if the fence is enabled and guided waypoint is within the fence // else return false if the waypoint is outside the fence bool Copter::ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { // ensure we are in position control mode if (guided_mode != Guided_WP) { pos_control_start(); } #if AC_FENCE == ENABLED // reject destination if outside the fence const Location dest_loc(destination); if (!copter.fence.check_destination_within_fence(dest_loc)) { copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } #endif // set yaw state set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); // no need to check return status because terrain data is not used wp_nav->set_wp_destination(destination, false); // log target copter.Log_Write_GuidedTarget(guided_mode, destination, Vector3f()); return true; }
// sets guided mode's target from a Location object // returns false if destination could not be set (probably caused by missing terrain data) // or if the fence is enabled and guided waypoint is outside the fence bool Copter::ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { // ensure we are in position control mode if (guided_mode != Guided_WP) { pos_control_start(); } #if AC_FENCE == ENABLED // reject destination outside the fence. // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails if (!copter.fence.check_destination_within_fence(dest_loc)) { copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } #endif if (!wp_nav->set_wp_destination(dest_loc)) { // failure to set destination can only be because of missing terrain data copter.Log_Write_Error(ERROR_SUBSYSTEM_NAVIGATION, ERROR_CODE_FAILED_TO_SET_DESTINATION); // failure is propagated to GCS with NAK return false; } // set yaw state set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); // log target copter.Log_Write_GuidedTarget(guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt),Vector3f()); return true; }
// guided_init - initialise guided controller bool Copter::ModeGuided::init(bool ignore_checks) { if (copter.position_ok() || ignore_checks) { // start in position control mode pos_control_start(); return true; }else{ return false; } }
// guided_init - initialise guided controller bool Copter::ModeGuided::init(bool ignore_checks) { // start in position control mode pos_control_start(); return true; }