mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Sub: Add camera slew rate parameter
This commit is contained in:
parent
0966dcb665
commit
fae6c084ac
@ -219,12 +219,10 @@ void Sub::fifty_hz_loop()
|
||||
// check pilot input failsafe
|
||||
failsafe_manual_control_check();
|
||||
|
||||
if (hal.rcin->new_input()) {
|
||||
// Update servo output
|
||||
RC_Channels::set_pwm_all();
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_mount_tilt, 20.0f, 0.02f);
|
||||
SRV_Channels::output_ch_all();
|
||||
}
|
||||
// Update servo output
|
||||
RC_Channels::set_pwm_all();
|
||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_mount_tilt, g.cam_slew_limit, 0.02f);
|
||||
SRV_Channels::output_ch_all();
|
||||
}
|
||||
|
||||
// update_mount - update camera mount position
|
||||
|
@ -799,6 +799,8 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),
|
||||
|
||||
GSCALAR(cam_slew_limit, "CAM_SLEW_LIMIT", 45.0),
|
||||
|
||||
// @Group:
|
||||
// @Path: Parameters.cpp
|
||||
GOBJECT(g2, "", ParametersG2),
|
||||
|
@ -227,6 +227,8 @@ public:
|
||||
k_param_radio_tuning_high, // Disabled
|
||||
k_param_radio_tuning_low, // Disabled
|
||||
|
||||
k_param_cam_slew_limit,
|
||||
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
@ -352,6 +354,7 @@ public:
|
||||
AP_Float surface_depth;
|
||||
AP_Int8 frame_configuration;
|
||||
|
||||
AP_Float cam_slew_limit;
|
||||
// Note: keep initializers here in the same order as they are declared
|
||||
// above.
|
||||
Parameters() :
|
||||
|
Loading…
Reference in New Issue
Block a user