mirror of https://github.com/ArduPilot/ardupilot
Tracker: add parameters for yaw and pitch scan speed
This commit is contained in:
parent
9ca2c9d692
commit
a967caa924
|
@ -64,15 +64,6 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(pitch_slew_time, "PITCH_SLEW_TIME", 2),
|
||||
|
||||
// @Param: SCAN_SPEED
|
||||
// @DisplayName: Speed at which to rotate in scan mode
|
||||
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
|
||||
// @Units: deg/s
|
||||
// @Increment: 1
|
||||
// @Range: 0 100
|
||||
// @User: Standard
|
||||
GSCALAR(scan_speed, "SCAN_SPEED", 5),
|
||||
|
||||
// @Param: MIN_REVERSE_TIME
|
||||
// @DisplayName: Minimum time to apply a yaw reversal
|
||||
// @Description: When the tracker detects it has reached the limit of servo movement in yaw it will reverse and try moving to the other extreme of yaw. This parameter controls the minimum time it should reverse for. It is used to cope with trackers that have a significant lag in movement to ensure they do move all the way around.
|
||||
|
@ -394,6 +385,24 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @Bitmask: 0:Pitch,1:Yaw
|
||||
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
|
||||
|
||||
// @Param: SCAN_SPEED_YAW
|
||||
// @DisplayName: Speed at which to rotate the yaw axis in scan mode
|
||||
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
|
||||
// @Units: deg/s
|
||||
// @Increment: 1
|
||||
// @Range: 0 100
|
||||
// @User: Standard
|
||||
GSCALAR(scan_speed_yaw, "SCAN_SPEED_YAW", 2),
|
||||
|
||||
// @Param: SCAN_SPEED_PIT
|
||||
// @DisplayName: Speed at which to rotate pitch axis in scan mode
|
||||
// @Description: This controls how rapidly the tracker will move the servos in SCAN mode
|
||||
// @Units: deg/s
|
||||
// @Increment: 1
|
||||
// @Range: 0 100
|
||||
// @User: Standard
|
||||
GSCALAR(scan_speed_pitch, "SCAN_SPEED_PIT", 5),
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
|
|
@ -69,7 +69,7 @@ public:
|
|||
k_param_startup_delay,
|
||||
k_param_BoardConfig,
|
||||
k_param_gps,
|
||||
k_param_scan_speed,
|
||||
k_param_scan_speed_unused, // deprecated
|
||||
k_param_proxy_mode_unused, // deprecated
|
||||
k_param_servo_pitch_type,
|
||||
k_param_onoff_yaw_rate,
|
||||
|
@ -117,6 +117,8 @@ public:
|
|||
|
||||
// 254,255: reserved
|
||||
k_param_gcs_pid_mask = 225,
|
||||
k_param_scan_speed_yaw,
|
||||
k_param_scan_speed_pitch,
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
|
@ -132,7 +134,8 @@ public:
|
|||
AP_Float yaw_slew_time;
|
||||
AP_Float pitch_slew_time;
|
||||
AP_Float min_reverse_time;
|
||||
AP_Float scan_speed;
|
||||
AP_Int16 scan_speed_yaw;
|
||||
AP_Int16 scan_speed_pitch;
|
||||
|
||||
AP_Float start_latitude;
|
||||
AP_Float start_longitude;
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
void Tracker::update_scan(void)
|
||||
{
|
||||
if (!nav_status.manual_control_yaw) {
|
||||
float yaw_delta = g.scan_speed * 0.02f;
|
||||
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;
|
||||
|
@ -23,7 +23,7 @@ void Tracker::update_scan(void)
|
|||
}
|
||||
|
||||
if (!nav_status.manual_control_pitch) {
|
||||
float pitch_delta = g.scan_speed * 0.02f;
|
||||
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 < -90 && nav_status.scan_reverse_pitch) {
|
||||
nav_status.scan_reverse_pitch = false;
|
||||
|
|
Loading…
Reference in New Issue