mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Tracker: Added parameter for mavlink update rate
This commit is contained in:
parent
8036912173
commit
17355baa83
@ -508,7 +508,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
|
||||
msg->sysid,
|
||||
msg->compid,
|
||||
MAV_DATA_STREAM_POSITION,
|
||||
1, // 1hz
|
||||
g.mavlink_update_rate, // 1hz
|
||||
1); // start streaming
|
||||
}
|
||||
// request air pressure
|
||||
@ -518,7 +518,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
|
||||
msg->sysid,
|
||||
msg->compid,
|
||||
MAV_DATA_STREAM_RAW_SENSORS,
|
||||
1, // 1hz
|
||||
g.mavlink_update_rate, // 1hz
|
||||
1); // start streaming
|
||||
}
|
||||
}
|
||||
|
@ -221,6 +221,15 @@ const AP_Param::Info Tracker::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(alt_source, "ALT_SOURCE", 0),
|
||||
|
||||
// @Param: MAV_UPDATE_RATE
|
||||
// @DisplayName: Mavlink Update Rate
|
||||
// @Description: The rate at which Mavlink updates position and baro data
|
||||
// @Units: hertz
|
||||
// @Increment: 1
|
||||
// @Range: 1 10
|
||||
// @User: Standard
|
||||
GSCALAR(mavlink_update_rate, "MAV_UPDATE_RATE", 1),
|
||||
|
||||
// barometer ground calibration. The GND_ prefix is chosen for
|
||||
// compatibility with previous releases of ArduPlane
|
||||
// @Group: GND_
|
||||
|
@ -100,6 +100,7 @@ public:
|
||||
k_param_serial_manager, // serial manager library
|
||||
k_param_servo_yaw_type,
|
||||
k_param_alt_source,
|
||||
k_param_mavlink_update_rate,
|
||||
|
||||
//
|
||||
// 200 : Radio settings
|
||||
@ -138,6 +139,7 @@ public:
|
||||
AP_Int8 servo_pitch_type;
|
||||
AP_Int8 servo_yaw_type;
|
||||
AP_Int8 alt_source;
|
||||
AP_Int8 mavlink_update_rate;
|
||||
AP_Float onoff_yaw_rate;
|
||||
AP_Float onoff_pitch_rate;
|
||||
AP_Float onoff_yaw_mintime;
|
||||
|
Loading…
Reference in New Issue
Block a user