mirror of https://github.com/ArduPilot/ardupilot
Tracker: minor parameter description and comment fix
This commit is contained in:
parent
ef60c202b4
commit
9bdbf7785f
|
@ -508,7 +508,7 @@ void Tracker::mavlink_check_target(const mavlink_message_t* msg)
|
|||
msg->sysid,
|
||||
msg->compid,
|
||||
MAV_DATA_STREAM_POSITION,
|
||||
g.mavlink_update_rate, // 1hz
|
||||
g.mavlink_update_rate,
|
||||
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,
|
||||
g.mavlink_update_rate, // 1hz
|
||||
g.mavlink_update_rate,
|
||||
1); // start streaming
|
||||
}
|
||||
}
|
||||
|
|
|
@ -224,7 +224,7 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @Param: MAV_UPDATE_RATE
|
||||
// @DisplayName: Mavlink Update Rate
|
||||
// @Description: The rate at which Mavlink updates position and baro data
|
||||
// @Units: hertz
|
||||
// @Units: Hz
|
||||
// @Increment: 1
|
||||
// @Range: 1 10
|
||||
// @User: Standard
|
||||
|
|
Loading…
Reference in New Issue