mirror of https://github.com/ArduPilot/ardupilot
Tracker: move update_scan into mode.cpp
Consolidating Mode:: methods in mode.cpp
This commit is contained in:
parent
f3d3f01e76
commit
1e451e8165
|
@ -1,42 +0,0 @@
|
|||
#include "Tracker.h"
|
||||
|
||||
/*
|
||||
* Scan control mode
|
||||
*/
|
||||
|
||||
/*
|
||||
* update_scan - runs the scan controller
|
||||
* called at 50hz while control mode is 'SCAN'
|
||||
*/
|
||||
void Mode::update_scan(void)
|
||||
{
|
||||
struct Tracker::NavStatus &nav_status = tracker.nav_status;
|
||||
|
||||
Parameters &g = tracker.g;
|
||||
|
||||
if (!nav_status.manual_control_yaw) {
|
||||
float yaw_delta = g.scan_speed_yaw * 0.02f;
|
||||
nav_status.bearing += yaw_delta * (nav_status.scan_reverse_yaw?-1:1);
|
||||
if (nav_status.bearing < 0 && nav_status.scan_reverse_yaw) {
|
||||
nav_status.scan_reverse_yaw = false;
|
||||
}
|
||||
if (nav_status.bearing > 360 && !nav_status.scan_reverse_yaw) {
|
||||
nav_status.scan_reverse_yaw = true;
|
||||
}
|
||||
nav_status.bearing = constrain_float(nav_status.bearing, 0, 360);
|
||||
}
|
||||
|
||||
if (!nav_status.manual_control_pitch) {
|
||||
float pitch_delta = g.scan_speed_pitch * 0.02f;
|
||||
nav_status.pitch += pitch_delta * (nav_status.scan_reverse_pitch?-1:1);
|
||||
if (nav_status.pitch < g.pitch_min && nav_status.scan_reverse_pitch) {
|
||||
nav_status.scan_reverse_pitch = false;
|
||||
}
|
||||
if (nav_status.pitch > g.pitch_max && !nav_status.scan_reverse_pitch) {
|
||||
nav_status.scan_reverse_pitch = true;
|
||||
}
|
||||
nav_status.pitch = constrain_float(nav_status.pitch, -g.pitch_min, g.pitch_max);
|
||||
}
|
||||
|
||||
update_auto();
|
||||
}
|
|
@ -32,6 +32,39 @@ void Mode::update_auto(void)
|
|||
}
|
||||
}
|
||||
|
||||
void Mode::update_scan(void)
|
||||
{
|
||||
struct Tracker::NavStatus &nav_status = tracker.nav_status;
|
||||
|
||||
Parameters &g = tracker.g;
|
||||
|
||||
if (!nav_status.manual_control_yaw) {
|
||||
float yaw_delta = g.scan_speed_yaw * 0.02f;
|
||||
nav_status.bearing += yaw_delta * (nav_status.scan_reverse_yaw?-1:1);
|
||||
if (nav_status.bearing < 0 && nav_status.scan_reverse_yaw) {
|
||||
nav_status.scan_reverse_yaw = false;
|
||||
}
|
||||
if (nav_status.bearing > 360 && !nav_status.scan_reverse_yaw) {
|
||||
nav_status.scan_reverse_yaw = true;
|
||||
}
|
||||
nav_status.bearing = constrain_float(nav_status.bearing, 0, 360);
|
||||
}
|
||||
|
||||
if (!nav_status.manual_control_pitch) {
|
||||
float pitch_delta = g.scan_speed_pitch * 0.02f;
|
||||
nav_status.pitch += pitch_delta * (nav_status.scan_reverse_pitch?-1:1);
|
||||
if (nav_status.pitch < g.pitch_min && nav_status.scan_reverse_pitch) {
|
||||
nav_status.scan_reverse_pitch = false;
|
||||
}
|
||||
if (nav_status.pitch > g.pitch_max && !nav_status.scan_reverse_pitch) {
|
||||
nav_status.scan_reverse_pitch = true;
|
||||
}
|
||||
nav_status.pitch = constrain_float(nav_status.pitch, -g.pitch_min, g.pitch_max);
|
||||
}
|
||||
|
||||
update_auto();
|
||||
}
|
||||
|
||||
void Mode::calc_angle_error(float pitch, float yaw, bool direction_reversed)
|
||||
{
|
||||
// Pitch angle error in centidegrees
|
||||
|
|
Loading…
Reference in New Issue