Browse Source

绕圈航线机头方向

celiu-4.0.17-rc8
zbr3550 4 years ago
parent
commit
683122b72b
  1. 1
      ArduCopter/UserCode.cpp
  2. 2
      ArduCopter/autoyaw.cpp
  3. 1
      ArduCopter/mode_auto.cpp

1
ArduCopter/UserCode.cpp

@ -51,7 +51,6 @@ void Copter::userhook_SuperSlowLoop() @@ -51,7 +51,6 @@ void Copter::userhook_SuperSlowLoop()
{
// put your 1Hz code here
zr_SuperSlowLoop();
}
#endif

2
ArduCopter/autoyaw.cpp

@ -8,7 +8,7 @@ float Mode::AutoYaw::roi_yaw() @@ -8,7 +8,7 @@ float Mode::AutoYaw::roi_yaw()
roi_yaw_counter++;
if (roi_yaw_counter >= 4) {
roi_yaw_counter = 0;
_roi_yaw = get_bearing_cd(copter.inertial_nav.get_position(), roi);
_roi_yaw = get_bearing_cd(copter.inertial_nav.get_position(), roi)+27000;
}
return _roi_yaw;

1
ArduCopter/mode_auto.cpp

@ -448,6 +448,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) @@ -448,6 +448,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
break;
case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
do_roi(cmd);
do_circle(cmd);
break;

Loading…
Cancel
Save