2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
2023-05-07 04:41:48 -03:00
|
|
|
#include <AP_Mount/AP_Mount.h>
|
2015-05-29 23:12:49 -03:00
|
|
|
|
2018-02-23 05:51:17 -04:00
|
|
|
#if MODE_CIRCLE_ENABLED == ENABLED
|
|
|
|
|
2014-01-27 01:09:48 -04:00
|
|
|
/*
|
2016-07-25 15:45:29 -03:00
|
|
|
* Init and run calls for circle flight mode
|
2014-01-27 01:09:48 -04:00
|
|
|
*/
|
|
|
|
|
2014-04-16 04:21:30 -03:00
|
|
|
// circle_init - initialise circle controller flight mode
|
2019-05-09 23:18:49 -03:00
|
|
|
bool ModeCircle::init(bool ignore_checks)
|
2014-01-27 01:09:48 -04:00
|
|
|
{
|
2020-01-06 18:37:04 -04:00
|
|
|
speed_changing = false;
|
2014-04-29 23:17:59 -03:00
|
|
|
|
2021-05-19 11:07:38 -03:00
|
|
|
// set speed and acceleration limits
|
2021-05-11 01:42:02 -03:00
|
|
|
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
2021-07-08 01:17:41 -03:00
|
|
|
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
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);
|
2021-07-08 01:17:41 -03:00
|
|
|
pos_control->set_correction_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
|
2014-04-29 23:17:59 -03:00
|
|
|
|
2019-02-28 20:52:28 -04:00
|
|
|
// initialise circle controller including setting the circle center based on vehicle speed
|
|
|
|
copter.circle_nav->init();
|
2014-05-07 03:06:34 -03:00
|
|
|
|
2023-05-07 04:41:48 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
|
|
|
// Check if the CIRCLE_OPTIONS parameter have roi_at_center
|
|
|
|
if (copter.circle_nav->roi_at_center()) {
|
2023-09-06 04:21:13 -03:00
|
|
|
const Vector3p &pos { copter.circle_nav->get_center() };
|
|
|
|
Location circle_center;
|
2024-06-06 07:56:27 -03:00
|
|
|
if (!AP::ahrs().get_location_from_origin_offset_NED(circle_center, pos * 0.01)) {
|
2023-09-06 04:21:13 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// point at the ground:
|
|
|
|
circle_center.set_alt_cm(0, Location::AltFrame::ABOVE_TERRAIN);
|
2024-06-15 22:23:03 -03:00
|
|
|
AP_Mount *s = AP_Mount::get_singleton();
|
2023-05-07 04:41:48 -03:00
|
|
|
s->set_roi_target(circle_center);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2022-10-06 21:38:52 -03:00
|
|
|
// set auto yaw circle mode
|
|
|
|
auto_yaw.set_mode(AutoYaw::Mode::CIRCLE);
|
|
|
|
|
2019-02-28 20:52:28 -04:00
|
|
|
return true;
|
2014-01-27 01:09:48 -04:00
|
|
|
}
|
|
|
|
|
2014-01-27 10:43:22 -04:00
|
|
|
// circle_run - runs the circle flight mode
|
2014-01-27 01:09:48 -04:00
|
|
|
// should be called at 100hz or more
|
2019-05-09 23:18:49 -03:00
|
|
|
void ModeCircle::run()
|
2014-01-27 01:09:48 -04:00
|
|
|
{
|
2021-05-19 11:07:38 -03:00
|
|
|
// set speed and acceleration limits
|
2021-05-11 01:42:02 -03:00
|
|
|
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
|
|
|
pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
|
2019-02-28 05:03:23 -04:00
|
|
|
|
2021-05-01 21:41:53 -03:00
|
|
|
// Check for any change in params and update in real time
|
|
|
|
copter.circle_nav->check_param_change();
|
|
|
|
|
2020-01-06 18:37:04 -04:00
|
|
|
// pilot changes to circle rate and radius
|
|
|
|
// skip if in radio failsafe
|
|
|
|
if (!copter.failsafe.radio && copter.circle_nav->pilot_control_enabled()) {
|
|
|
|
// update the circle controller's radius target based on pilot pitch stick inputs
|
|
|
|
const float radius_current = copter.circle_nav->get_radius(); // circle controller's radius target, which begins as the circle_radius parameter
|
|
|
|
const float pitch_stick = channel_pitch->norm_input_dz(); // pitch stick normalized -1 to 1
|
|
|
|
const float nav_speed = copter.wp_nav->get_default_speed_xy(); // copter WP_NAV parameter speed
|
2020-02-03 17:23:08 -04:00
|
|
|
const float radius_pilot_change = (pitch_stick * nav_speed) * G_Dt; // rate of change (pitch stick up reduces the radius, as in moving forward)
|
2020-01-06 18:37:04 -04:00
|
|
|
const float radius_new = MAX(radius_current + radius_pilot_change,0); // new radius target
|
|
|
|
|
|
|
|
if (!is_equal(radius_current, radius_new)) {
|
2022-02-06 12:35:17 -04:00
|
|
|
copter.circle_nav->set_radius_cm(radius_new);
|
2020-01-06 18:37:04 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// update the orbicular rate target based on pilot roll stick inputs
|
|
|
|
// skip if using CH6 tuning knob for circle rate
|
|
|
|
if (g.radio_tuning != TUNING_CIRCLE_RATE) {
|
|
|
|
const float roll_stick = channel_roll->norm_input_dz(); // roll stick normalized -1 to 1
|
|
|
|
|
|
|
|
if (is_zero(roll_stick)) {
|
|
|
|
// no speed change, so reset speed changing flag
|
|
|
|
speed_changing = false;
|
|
|
|
} else {
|
|
|
|
const float rate = copter.circle_nav->get_rate(); // circle controller's rate target, which begins as the circle_rate parameter
|
|
|
|
const float rate_current = copter.circle_nav->get_rate_current(); // current adjusted rate target, which is probably different from _rate
|
|
|
|
const float rate_pilot_change = (roll_stick * G_Dt); // rate of change from 0 to 1 degrees per second
|
|
|
|
float rate_new = rate_current; // new rate target
|
|
|
|
if (is_positive(rate)) {
|
|
|
|
// currently moving clockwise, constrain 0 to 90
|
|
|
|
rate_new = constrain_float(rate_current + rate_pilot_change, 0, 90);
|
|
|
|
|
|
|
|
} else if (is_negative(rate)) {
|
|
|
|
// currently moving counterclockwise, constrain -90 to 0
|
|
|
|
rate_new = constrain_float(rate_current + rate_pilot_change, -90, 0);
|
|
|
|
|
|
|
|
} else if (is_zero(rate) && !speed_changing) {
|
|
|
|
// Stopped, pilot has released the roll stick, and pilot now wants to begin moving with the roll stick
|
|
|
|
rate_new = rate_pilot_change;
|
|
|
|
}
|
|
|
|
|
|
|
|
speed_changing = true;
|
|
|
|
copter.circle_nav->set_rate(rate_new);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-02-28 05:03:23 -04:00
|
|
|
// get pilot desired climb rate (or zero if in radio failsafe)
|
|
|
|
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
|
|
|
|
|
2022-06-12 11:12:14 -03:00
|
|
|
// get avoidance adjusted climb rate
|
|
|
|
target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
|
|
|
|
|
2019-02-28 05:03:23 -04:00
|
|
|
// if not armed set throttle to zero and exit immediately
|
2019-04-08 05:15:57 -03:00
|
|
|
if (is_disarmed_or_landed()) {
|
2020-10-13 20:19:42 -03:00
|
|
|
make_safe_ground_handling();
|
2019-02-28 05:03:23 -04:00
|
|
|
return;
|
2014-01-27 01:09:48 -04:00
|
|
|
}
|
|
|
|
|
2016-01-13 03:10:00 -04:00
|
|
|
// set motors to full range
|
2019-04-09 09:16:58 -03:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
2016-01-13 03:10:00 -04:00
|
|
|
|
2021-08-31 01:17:59 -03:00
|
|
|
// update the vertical offset based on the surface measurement
|
|
|
|
copter.surface_tracking.update_surface_offset();
|
|
|
|
|
2021-05-11 01:42:02 -03:00
|
|
|
copter.failsafe_terrain_set_status(copter.circle_nav->update(target_climb_rate));
|
2017-01-09 03:31:26 -04:00
|
|
|
pos_control->update_z_controller();
|
2022-09-24 11:12:33 -03:00
|
|
|
|
|
|
|
// call attitude controller with auto yaw
|
|
|
|
attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading());
|
2014-01-27 01:09:48 -04:00
|
|
|
}
|
2018-02-07 22:21:09 -04:00
|
|
|
|
2019-05-09 23:18:49 -03:00
|
|
|
uint32_t ModeCircle::wp_distance() const
|
2018-02-07 22:21:09 -04:00
|
|
|
{
|
2018-03-27 23:10:13 -03:00
|
|
|
return copter.circle_nav->get_distance_to_target();
|
2018-02-07 22:21:09 -04:00
|
|
|
}
|
|
|
|
|
2019-05-09 23:18:49 -03:00
|
|
|
int32_t ModeCircle::wp_bearing() const
|
2018-02-07 22:21:09 -04:00
|
|
|
{
|
2018-03-27 23:10:13 -03:00
|
|
|
return copter.circle_nav->get_bearing_to_target();
|
2018-02-07 22:21:09 -04:00
|
|
|
}
|
2018-02-23 05:51:17 -04:00
|
|
|
|
|
|
|
#endif
|