control_guided.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577
  1. #include "Sub.h"
  2. /*
  3. * Init and run calls for guided flight mode
  4. */
  5. #ifndef GUIDED_LOOK_AT_TARGET_MIN_DISTANCE_CM
  6. # define GUIDED_LOOK_AT_TARGET_MIN_DISTANCE_CM 500 // point nose at target if it is more than 5m away
  7. #endif
  8. #define GUIDED_POSVEL_TIMEOUT_MS 3000 // guided mode's position-velocity controller times out after 3seconds with no new updates
  9. #define GUIDED_ATTITUDE_TIMEOUT_MS 1000 // guided mode's attitude controller times out after 1 second with no new updates
  10. static Vector3f posvel_pos_target_cm;
  11. static Vector3f posvel_vel_target_cms;
  12. static uint32_t posvel_update_time_ms;
  13. static uint32_t vel_update_time_ms;
  14. struct {
  15. uint32_t update_time_ms;
  16. float roll_cd;
  17. float pitch_cd;
  18. float yaw_cd;
  19. float climb_rate_cms;
  20. } static guided_angle_state = {0,0.0f, 0.0f, 0.0f, 0.0f};
  21. struct Guided_Limit {
  22. uint32_t timeout_ms; // timeout (in seconds) from the time that guided is invoked
  23. float alt_min_cm; // lower altitude limit in cm above home (0 = no limit)
  24. float alt_max_cm; // upper altitude limit in cm above home (0 = no limit)
  25. float horiz_max_cm; // horizontal position limit in cm from where guided mode was initiated (0 = no limit)
  26. uint32_t start_time;// system time in milliseconds that control was handed to the external computer
  27. Vector3f start_pos; // start position as a distance from home in cm. used for checking horiz_max limit
  28. } guided_limit;
  29. // guided_init - initialise guided controller
  30. bool Sub::guided_init(bool ignore_checks)
  31. {
  32. if (!position_ok() && !ignore_checks) {
  33. return false;
  34. }
  35. // initialise yaw
  36. set_auto_yaw_mode(get_default_auto_yaw_mode(false));
  37. // start in position control mode
  38. guided_pos_control_start();
  39. return true;
  40. }
  41. // initialise guided mode's position controller
  42. void Sub::guided_pos_control_start()
  43. {
  44. // set to position control mode
  45. guided_mode = Guided_WP;
  46. // initialise waypoint and spline controller
  47. wp_nav.wp_and_spline_init();
  48. // initialise wpnav to stopping point at current altitude
  49. // To-Do: set to current location if disarmed?
  50. // To-Do: set to stopping point altitude?
  51. Vector3f stopping_point;
  52. stopping_point.z = inertial_nav.get_altitude();
  53. wp_nav.get_wp_stopping_point_xy(stopping_point);
  54. // no need to check return status because terrain data is not used
  55. wp_nav.set_wp_destination(stopping_point, false);
  56. // initialise yaw
  57. set_auto_yaw_mode(get_default_auto_yaw_mode(false));
  58. }
  59. // initialise guided mode's velocity controller
  60. void Sub::guided_vel_control_start()
  61. {
  62. // set guided_mode to velocity controller
  63. guided_mode = Guided_Velocity;
  64. // initialize vertical speeds and leash lengths
  65. pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
  66. pos_control.set_max_accel_z(g.pilot_accel_z);
  67. // initialise velocity controller
  68. pos_control.init_vel_controller_xyz();
  69. }
  70. // initialise guided mode's posvel controller
  71. void Sub::guided_posvel_control_start()
  72. {
  73. // set guided_mode to velocity controller
  74. guided_mode = Guided_PosVel;
  75. pos_control.init_xy_controller();
  76. // set speed and acceleration from wpnav's speed and acceleration
  77. pos_control.set_max_speed_xy(wp_nav.get_default_speed_xy());
  78. pos_control.set_max_accel_xy(wp_nav.get_wp_acceleration());
  79. const Vector3f& curr_pos = inertial_nav.get_position();
  80. const Vector3f& curr_vel = inertial_nav.get_velocity();
  81. // set target position and velocity to current position and velocity
  82. pos_control.set_xy_target(curr_pos.x, curr_pos.y);
  83. pos_control.set_desired_velocity_xy(curr_vel.x, curr_vel.y);
  84. // set vertical speed and acceleration
  85. pos_control.set_max_speed_z(wp_nav.get_default_speed_down(), wp_nav.get_default_speed_up());
  86. pos_control.set_max_accel_z(wp_nav.get_accel_z());
  87. // pilot always controls yaw
  88. set_auto_yaw_mode(AUTO_YAW_HOLD);
  89. }
  90. // initialise guided mode's angle controller
  91. void Sub::guided_angle_control_start()
  92. {
  93. // set guided_mode to velocity controller
  94. guided_mode = Guided_Angle;
  95. // set vertical speed and acceleration
  96. pos_control.set_max_speed_z(wp_nav.get_default_speed_down(), wp_nav.get_default_speed_up());
  97. pos_control.set_max_accel_z(wp_nav.get_accel_z());
  98. // initialise position and desired velocity
  99. pos_control.set_alt_target(inertial_nav.get_altitude());
  100. pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z());
  101. // initialise targets
  102. guided_angle_state.update_time_ms = AP_HAL::millis();
  103. guided_angle_state.roll_cd = ahrs.roll_sensor;
  104. guided_angle_state.pitch_cd = ahrs.pitch_sensor;
  105. guided_angle_state.yaw_cd = ahrs.yaw_sensor;
  106. guided_angle_state.climb_rate_cms = 0.0f;
  107. // pilot always controls yaw
  108. set_auto_yaw_mode(AUTO_YAW_HOLD);
  109. }
  110. // guided_set_destination - sets guided mode's target destination
  111. // Returns true if the fence is enabled and guided waypoint is within the fence
  112. // else return false if the waypoint is outside the fence
  113. bool Sub::guided_set_destination(const Vector3f& destination)
  114. {
  115. // ensure we are in position control mode
  116. if (guided_mode != Guided_WP) {
  117. guided_pos_control_start();
  118. }
  119. #if AC_FENCE == ENABLED
  120. // reject destination if outside the fence
  121. const Location dest_loc(destination);
  122. if (!fence.check_destination_within_fence(dest_loc)) {
  123. AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
  124. // failure is propagated to GCS with NAK
  125. return false;
  126. }
  127. #endif
  128. // no need to check return status because terrain data is not used
  129. wp_nav.set_wp_destination(destination, false);
  130. // log target
  131. Log_Write_GuidedTarget(guided_mode, destination, Vector3f());
  132. return true;
  133. }
  134. // sets guided mode's target from a Location object
  135. // returns false if destination could not be set (probably caused by missing terrain data)
  136. // or if the fence is enabled and guided waypoint is outside the fence
  137. bool Sub::guided_set_destination(const Location& dest_loc)
  138. {
  139. // ensure we are in position control mode
  140. if (guided_mode != Guided_WP) {
  141. guided_pos_control_start();
  142. }
  143. #if AC_FENCE == ENABLED
  144. // reject destination outside the fence.
  145. // 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
  146. if (!fence.check_destination_within_fence(dest_loc)) {
  147. AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
  148. // failure is propagated to GCS with NAK
  149. return false;
  150. }
  151. #endif
  152. if (!wp_nav.set_wp_destination(dest_loc)) {
  153. // failure to set destination can only be because of missing terrain data
  154. AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
  155. // failure is propagated to GCS with NAK
  156. return false;
  157. }
  158. // log target
  159. Log_Write_GuidedTarget(guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt),Vector3f());
  160. return true;
  161. }
  162. // guided_set_velocity - sets guided mode's target velocity
  163. void Sub::guided_set_velocity(const Vector3f& velocity)
  164. {
  165. // check we are in velocity control mode
  166. if (guided_mode != Guided_Velocity) {
  167. guided_vel_control_start();
  168. }
  169. vel_update_time_ms = AP_HAL::millis();
  170. // set position controller velocity target
  171. pos_control.set_desired_velocity(velocity);
  172. }
  173. // set guided mode posvel target
  174. bool Sub::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity)
  175. {
  176. // check we are in velocity control mode
  177. if (guided_mode != Guided_PosVel) {
  178. guided_posvel_control_start();
  179. }
  180. #if AC_FENCE == ENABLED
  181. // reject destination if outside the fence
  182. const Location dest_loc(destination);
  183. if (!fence.check_destination_within_fence(dest_loc)) {
  184. AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE);
  185. // failure is propagated to GCS with NAK
  186. return false;
  187. }
  188. #endif
  189. posvel_update_time_ms = AP_HAL::millis();
  190. posvel_pos_target_cm = destination;
  191. posvel_vel_target_cms = velocity;
  192. pos_control.set_pos_target(posvel_pos_target_cm);
  193. // log target
  194. Log_Write_GuidedTarget(guided_mode, destination, velocity);
  195. return true;
  196. }
  197. // set guided mode angle target
  198. void Sub::guided_set_angle(const Quaternion &q, float climb_rate_cms)
  199. {
  200. // check we are in velocity control mode
  201. if (guided_mode != Guided_Angle) {
  202. guided_angle_control_start();
  203. }
  204. // convert quaternion to euler angles
  205. q.to_euler(guided_angle_state.roll_cd, guided_angle_state.pitch_cd, guided_angle_state.yaw_cd);
  206. guided_angle_state.roll_cd = ToDeg(guided_angle_state.roll_cd) * 100.0f;
  207. guided_angle_state.pitch_cd = ToDeg(guided_angle_state.pitch_cd) * 100.0f;
  208. guided_angle_state.yaw_cd = wrap_180_cd(ToDeg(guided_angle_state.yaw_cd) * 100.0f);
  209. guided_angle_state.climb_rate_cms = climb_rate_cms;
  210. guided_angle_state.update_time_ms = AP_HAL::millis();
  211. }
  212. // guided_run - runs the guided controller
  213. // should be called at 100hz or more
  214. void Sub::guided_run()
  215. {
  216. // call the correct auto controller
  217. switch (guided_mode) {
  218. case Guided_WP:
  219. // run position controller
  220. guided_pos_control_run();
  221. break;
  222. case Guided_Velocity:
  223. // run velocity controller
  224. guided_vel_control_run();
  225. break;
  226. case Guided_PosVel:
  227. // run position-velocity controller
  228. guided_posvel_control_run();
  229. break;
  230. case Guided_Angle:
  231. // run angle controller
  232. guided_angle_control_run();
  233. break;
  234. }
  235. }
  236. // guided_pos_control_run - runs the guided position controller
  237. // called from guided_run
  238. void Sub::guided_pos_control_run()
  239. {
  240. // if motors not enabled set throttle to zero and exit immediately
  241. if (!motors.armed()) {
  242. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  243. // Sub vehicles do not stabilize roll/pitch/yaw when disarmed
  244. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  245. attitude_control.relax_attitude_controllers();
  246. return;
  247. }
  248. // process pilot's yaw input
  249. float target_yaw_rate = 0;
  250. if (!failsafe.pilot_input) {
  251. // get pilot's desired yaw rate
  252. target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  253. if (!is_zero(target_yaw_rate)) {
  254. set_auto_yaw_mode(AUTO_YAW_HOLD);
  255. }
  256. }
  257. // set motors to full range
  258. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  259. // run waypoint controller
  260. failsafe_terrain_set_status(wp_nav.update_wpnav());
  261. float lateral_out, forward_out;
  262. translate_wpnav_rp(lateral_out, forward_out);
  263. // Send to forward/lateral outputs
  264. motors.set_lateral(lateral_out);
  265. motors.set_forward(forward_out);
  266. // call z-axis position controller (wpnav should have already updated it's alt target)
  267. pos_control.update_z_controller();
  268. // call attitude controller
  269. if (auto_yaw_mode == AUTO_YAW_HOLD) {
  270. // roll & pitch from waypoint controller, yaw rate from pilot
  271. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
  272. } else {
  273. // roll, pitch from waypoint controller, yaw heading from auto_heading()
  274. attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
  275. }
  276. }
  277. // guided_vel_control_run - runs the guided velocity controller
  278. // called from guided_run
  279. void Sub::guided_vel_control_run()
  280. {
  281. // ifmotors not enabled set throttle to zero and exit immediately
  282. if (!motors.armed()) {
  283. // initialise velocity controller
  284. pos_control.init_vel_controller_xyz();
  285. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  286. // Sub vehicles do not stabilize roll/pitch/yaw when disarmed
  287. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  288. attitude_control.relax_attitude_controllers();
  289. return;
  290. }
  291. // process pilot's yaw input
  292. float target_yaw_rate = 0;
  293. if (!failsafe.pilot_input) {
  294. // get pilot's desired yaw rate
  295. target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  296. if (!is_zero(target_yaw_rate)) {
  297. set_auto_yaw_mode(AUTO_YAW_HOLD);
  298. }
  299. }
  300. // set motors to full range
  301. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  302. // set velocity to zero if no updates received for 3 seconds
  303. uint32_t tnow = AP_HAL::millis();
  304. if (tnow - vel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !pos_control.get_desired_velocity().is_zero()) {
  305. pos_control.set_desired_velocity(Vector3f(0,0,0));
  306. }
  307. // call velocity controller which includes z axis controller
  308. pos_control.update_vel_controller_xyz();
  309. float lateral_out, forward_out;
  310. translate_pos_control_rp(lateral_out, forward_out);
  311. // Send to forward/lateral outputs
  312. motors.set_lateral(lateral_out);
  313. motors.set_forward(forward_out);
  314. // call attitude controller
  315. if (auto_yaw_mode == AUTO_YAW_HOLD) {
  316. // roll & pitch from waypoint controller, yaw rate from pilot
  317. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
  318. } else {
  319. // roll, pitch from waypoint controller, yaw heading from auto_heading()
  320. attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
  321. }
  322. }
  323. // guided_posvel_control_run - runs the guided spline controller
  324. // called from guided_run
  325. void Sub::guided_posvel_control_run()
  326. {
  327. // if motors not enabled set throttle to zero and exit immediately
  328. if (!motors.armed()) {
  329. // set target position and velocity to current position and velocity
  330. pos_control.set_pos_target(inertial_nav.get_position());
  331. pos_control.set_desired_velocity(Vector3f(0,0,0));
  332. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  333. // Sub vehicles do not stabilize roll/pitch/yaw when disarmed
  334. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  335. attitude_control.relax_attitude_controllers();
  336. return;
  337. }
  338. // process pilot's yaw input
  339. float target_yaw_rate = 0;
  340. if (!failsafe.pilot_input) {
  341. // get pilot's desired yaw rate
  342. target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  343. if (!is_zero(target_yaw_rate)) {
  344. set_auto_yaw_mode(AUTO_YAW_HOLD);
  345. }
  346. }
  347. // set motors to full range
  348. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  349. // set velocity to zero if no updates received for 3 seconds
  350. uint32_t tnow = AP_HAL::millis();
  351. if (tnow - posvel_update_time_ms > GUIDED_POSVEL_TIMEOUT_MS && !posvel_vel_target_cms.is_zero()) {
  352. posvel_vel_target_cms.zero();
  353. }
  354. // calculate dt
  355. float dt = pos_control.time_since_last_xy_update();
  356. // sanity check dt
  357. if (dt >= 0.2f) {
  358. dt = 0.0f;
  359. }
  360. // advance position target using velocity target
  361. posvel_pos_target_cm += posvel_vel_target_cms * dt;
  362. // send position and velocity targets to position controller
  363. pos_control.set_pos_target(posvel_pos_target_cm);
  364. pos_control.set_desired_velocity_xy(posvel_vel_target_cms.x, posvel_vel_target_cms.y);
  365. // run position controller
  366. pos_control.update_xy_controller();
  367. float lateral_out, forward_out;
  368. translate_pos_control_rp(lateral_out, forward_out);
  369. // Send to forward/lateral outputs
  370. motors.set_lateral(lateral_out);
  371. motors.set_forward(forward_out);
  372. pos_control.update_z_controller();
  373. // call attitude controller
  374. if (auto_yaw_mode == AUTO_YAW_HOLD) {
  375. // roll & pitch from waypoint controller, yaw rate from pilot
  376. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
  377. } else {
  378. // roll, pitch from waypoint controller, yaw heading from auto_heading()
  379. attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true);
  380. }
  381. }
  382. // guided_angle_control_run - runs the guided angle controller
  383. // called from guided_run
  384. void Sub::guided_angle_control_run()
  385. {
  386. // if motors not enabled set throttle to zero and exit immediately
  387. if (!motors.armed()) {
  388. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  389. // Sub vehicles do not stabilize roll/pitch/yaw when disarmed
  390. attitude_control.set_throttle_out(0.0f,true,g.throttle_filt);
  391. attitude_control.relax_attitude_controllers();
  392. pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
  393. return;
  394. }
  395. // constrain desired lean angles
  396. float roll_in = guided_angle_state.roll_cd;
  397. float pitch_in = guided_angle_state.pitch_cd;
  398. float total_in = norm(roll_in, pitch_in);
  399. float angle_max = MIN(attitude_control.get_althold_lean_angle_max(), aparm.angle_max);
  400. if (total_in > angle_max) {
  401. float ratio = angle_max / total_in;
  402. roll_in *= ratio;
  403. pitch_in *= ratio;
  404. }
  405. // wrap yaw request
  406. float yaw_in = wrap_180_cd(guided_angle_state.yaw_cd);
  407. // constrain climb rate
  408. float climb_rate_cms = constrain_float(guided_angle_state.climb_rate_cms, -fabsf(wp_nav.get_default_speed_down()), wp_nav.get_default_speed_up());
  409. // check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds
  410. uint32_t tnow = AP_HAL::millis();
  411. if (tnow - guided_angle_state.update_time_ms > GUIDED_ATTITUDE_TIMEOUT_MS) {
  412. roll_in = 0.0f;
  413. pitch_in = 0.0f;
  414. climb_rate_cms = 0.0f;
  415. }
  416. // set motors to full range
  417. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  418. // call attitude controller
  419. attitude_control.input_euler_angle_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true);
  420. // call position controller
  421. pos_control.set_alt_target_from_climb_rate_ff(climb_rate_cms, G_Dt, false);
  422. pos_control.update_z_controller();
  423. }
  424. // Guided Limit code
  425. // guided_limit_clear - clear/turn off guided limits
  426. void Sub::guided_limit_clear()
  427. {
  428. guided_limit.timeout_ms = 0;
  429. guided_limit.alt_min_cm = 0.0f;
  430. guided_limit.alt_max_cm = 0.0f;
  431. guided_limit.horiz_max_cm = 0.0f;
  432. }
  433. // guided_limit_set - set guided timeout and movement limits
  434. void Sub::guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm)
  435. {
  436. guided_limit.timeout_ms = timeout_ms;
  437. guided_limit.alt_min_cm = alt_min_cm;
  438. guided_limit.alt_max_cm = alt_max_cm;
  439. guided_limit.horiz_max_cm = horiz_max_cm;
  440. }
  441. // guided_limit_init_time_and_pos - initialise guided start time and position as reference for limit checking
  442. // only called from AUTO mode's auto_nav_guided_start function
  443. void Sub::guided_limit_init_time_and_pos()
  444. {
  445. // initialise start time
  446. guided_limit.start_time = AP_HAL::millis();
  447. // initialise start position from current position
  448. guided_limit.start_pos = inertial_nav.get_position();
  449. }
  450. // guided_limit_check - returns true if guided mode has breached a limit
  451. // used when guided is invoked from the NAV_GUIDED_ENABLE mission command
  452. bool Sub::guided_limit_check()
  453. {
  454. // check if we have passed the timeout
  455. if ((guided_limit.timeout_ms > 0) && (AP_HAL::millis() - guided_limit.start_time >= guided_limit.timeout_ms)) {
  456. return true;
  457. }
  458. // get current location
  459. const Vector3f& curr_pos = inertial_nav.get_position();
  460. // check if we have gone below min alt
  461. if (!is_zero(guided_limit.alt_min_cm) && (curr_pos.z < guided_limit.alt_min_cm)) {
  462. return true;
  463. }
  464. // check if we have gone above max alt
  465. if (!is_zero(guided_limit.alt_max_cm) && (curr_pos.z > guided_limit.alt_max_cm)) {
  466. return true;
  467. }
  468. // check if we have gone beyond horizontal limit
  469. if (guided_limit.horiz_max_cm > 0.0f) {
  470. float horiz_move = get_horizontal_distance_cm(guided_limit.start_pos, curr_pos);
  471. if (horiz_move > guided_limit.horiz_max_cm) {
  472. return true;
  473. }
  474. }
  475. // if we got this far we must be within limits
  476. return false;
  477. }