mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove TELEM_DELAY parameter
This commit is contained in:
parent
4cb9ee947b
commit
57013583ac
|
@ -11,7 +11,7 @@ public:
|
|||
|
||||
protected:
|
||||
|
||||
uint32_t telem_delay() const override;
|
||||
uint32_t telem_delay() const override { return 0; };
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -96,15 +96,6 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
|
||||
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
|
||||
|
||||
// @Param: TELEM_DELAY
|
||||
// @DisplayName: Telemetry startup delay
|
||||
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
|
||||
// @User: Advanced
|
||||
// @Units: seconds
|
||||
// @Range: 0 10
|
||||
// @Increment: 1
|
||||
GSCALAR(telem_delay, "TELEM_DELAY", 0),
|
||||
|
||||
// @Param: GCS_PID_MASK
|
||||
// @DisplayName: GCS PID tuning mask
|
||||
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
|
||||
|
|
|
@ -138,7 +138,6 @@ public:
|
|||
k_param_gcs1,
|
||||
k_param_sysid_this_mav,
|
||||
k_param_sysid_my_gcs,
|
||||
k_param_telem_delay,
|
||||
k_param_gcs2,
|
||||
k_param_serial_manager,
|
||||
k_param_ch9_option,
|
||||
|
@ -297,7 +296,6 @@ public:
|
|||
//
|
||||
AP_Int16 sysid_this_mav;
|
||||
AP_Int16 sysid_my_gcs;
|
||||
AP_Int8 telem_delay;
|
||||
#if CLI_ENABLED == ENABLED
|
||||
AP_Int8 cli_enabled;
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue