control_poshold.cpp 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129
  1. // ArduSub position hold flight mode
  2. // GPS required
  3. // Jacob Walser August 2016
  4. #include "Sub.h"
  5. #if POSHOLD_ENABLED == ENABLED
  6. // poshold_init - initialise PosHold controller
  7. bool Sub::poshold_init()
  8. {
  9. // fail to initialise PosHold mode if no GPS lock
  10. if (!position_ok()) {
  11. return false;
  12. }
  13. // initialize vertical speeds and acceleration
  14. pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
  15. pos_control.set_max_accel_z(g.pilot_accel_z);
  16. // initialise position and desired velocity
  17. pos_control.set_alt_target(inertial_nav.get_altitude());
  18. pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z());
  19. // set target to current position
  20. // only init here as we can switch to PosHold in flight with a velocity <> 0 that will be used as _last_vel in PosControl and never updated again as we inhibit Reset_I
  21. loiter_nav.clear_pilot_desired_acceleration();
  22. loiter_nav.init_target();
  23. last_pilot_heading = ahrs.yaw_sensor;
  24. return true;
  25. }
  26. // poshold_run - runs the PosHold controller
  27. // should be called at 100hz or more
  28. void Sub::poshold_run()
  29. {
  30. uint32_t tnow = AP_HAL::millis();
  31. // if not armed set throttle to zero and exit immediately
  32. if (!motors.armed()) {
  33. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  34. loiter_nav.clear_pilot_desired_acceleration();
  35. loiter_nav.init_target();
  36. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  37. attitude_control.relax_attitude_controllers();
  38. pos_control.relax_alt_hold_controllers(motors.get_throttle_hover());
  39. return;
  40. }
  41. // set motors to full range
  42. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  43. // run loiter controller
  44. loiter_nav.update();
  45. ///////////////////////
  46. // update xy outputs //
  47. float pilot_lateral = channel_lateral->norm_input();
  48. float pilot_forward = channel_forward->norm_input();
  49. float lateral_out = 0;
  50. float forward_out = 0;
  51. // Allow pilot to reposition the sub
  52. if (fabsf(pilot_lateral) > 0.1 || fabsf(pilot_forward) > 0.1) {
  53. lateral_out = pilot_lateral;
  54. forward_out = pilot_forward;
  55. loiter_nav.clear_pilot_desired_acceleration();
  56. loiter_nav.init_target(); // initialize target to current position after repositioning
  57. } else {
  58. translate_wpnav_rp(lateral_out, forward_out);
  59. }
  60. motors.set_lateral(lateral_out);
  61. motors.set_forward(forward_out);
  62. /////////////////////
  63. // Update attitude //
  64. // get pilot's desired yaw rate
  65. float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  66. // convert pilot input to lean angles
  67. // To-Do: convert get_pilot_desired_lean_angles to return angles as floats
  68. float target_roll, target_pitch;
  69. get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
  70. // update attitude controller targets
  71. if (!is_zero(target_yaw_rate)) { // call attitude controller with rate yaw determined by pilot input
  72. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
  73. last_pilot_heading = ahrs.yaw_sensor;
  74. last_pilot_yaw_input_ms = tnow; // time when pilot last changed heading
  75. } else { // hold current heading
  76. // this check is required to prevent bounce back after very fast yaw maneuvers
  77. // the inertia of the vehicle causes the heading to move slightly past the point when pilot input actually stopped
  78. if (tnow < last_pilot_yaw_input_ms + 250) { // give 250ms to slow down, then set target heading
  79. target_yaw_rate = 0; // Stop rotation on yaw axis
  80. // call attitude controller with target yaw rate = 0 to decelerate on yaw axis
  81. attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
  82. last_pilot_heading = ahrs.yaw_sensor; // update heading to hold
  83. } else { // call attitude controller holding absolute absolute bearing
  84. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, last_pilot_heading, true);
  85. }
  86. }
  87. ///////////////////
  88. // Update z axis //
  89. // get pilot desired climb rate
  90. float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
  91. target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up);
  92. // call z axis position controller
  93. if (ap.at_bottom) {
  94. pos_control.relax_alt_hold_controllers(motors.get_throttle_hover()); // clear velocity and position targets, and integrator
  95. pos_control.set_alt_target(inertial_nav.get_altitude() + 10.0f); // set target to 10 cm above bottom
  96. } else {
  97. pos_control.set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
  98. }
  99. pos_control.update_z_controller();
  100. }
  101. #endif // POSHOLD_ENABLED == ENABLED