Skip to content

Commit

Permalink
Param MAV_ULOG_MAX_RT for ulog rate control
Browse files Browse the repository at this point in the history
  • Loading branch information
Jari Nippula committed Jan 25, 2024
1 parent 0357a57 commit e4e0960
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 1 deletion.
3 changes: 2 additions & 1 deletion src/modules/mavlink/mavlink_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -494,7 +494,7 @@ class Mavlink final : public ModuleParams
{
if (_mavlink_ulog) { return; }

_mavlink_ulog = MavlinkULog::try_start(_datarate, 0.7f, target_system, target_component);
_mavlink_ulog = MavlinkULog::try_start(_datarate, _param_mav_ulog_max_rate.get(), target_system, target_component);
}

const events::SendProtocol &get_events_protocol() const { return _events; };
Expand Down Expand Up @@ -675,6 +675,7 @@ class Mavlink final : public ModuleParams
(ParamBool<px4::params::MAV_HASH_CHK_EN>) _param_mav_hash_chk_en,
(ParamBool<px4::params::MAV_HB_FORW_EN>) _param_mav_hb_forw_en,
(ParamInt<px4::params::MAV_RADIO_TOUT>) _param_mav_radio_timeout,
(ParamFloat<px4::params::MAV_ULOG_MAX_RT>) _param_mav_ulog_max_rate,
(ParamInt<px4::params::SYS_HITL>) _param_sys_hitl,
(ParamBool<px4::params::SYS_FAILURE_EN>) _param_sys_failure_injection_enabled
)
Expand Down
9 changes: 9 additions & 0 deletions src/modules/mavlink/mavlink_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -155,3 +155,12 @@ PARAM_DEFINE_INT32(MAV_HB_FORW_EN, 1);
* @max 250
*/
PARAM_DEFINE_INT32(MAV_RADIO_TOUT, 5);

/**
* Maximum rate in msg/100ms for ULog streaming
*
* @group MAVLink
* @min 0.0
* @max 1.0
*/
PARAM_DEFINE_FLOAT(MAV_ULOG_MAX_RT, 0.5f);

0 comments on commit e4e0960

Please sign in to comment.