Skip to content

Commit

Permalink
AP_DDS: add params for ping timeout and max retries
Browse files Browse the repository at this point in the history
Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring authored and peterbarker committed Sep 24, 2024
1 parent 5f4a6dc commit a75b8a9
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 3 deletions.
23 changes: 20 additions & 3 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,25 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] {
// @User: Standard
AP_GROUPINFO("_DOMAIN_ID", 4, AP_DDS_Client, domain_id, 0),

// @Param: _TIMEOUT_MS
// @DisplayName: DDS ping timeout
// @Description: The time in milliseconds the DDS client will wait for a response from the XRCE agent before reattempting.
// @Units: ms
// @Range: 1 10000
// @RebootRequired: True
// @Increment: 1
// @User: Standard
AP_GROUPINFO("_TIMEOUT_MS", 5, AP_DDS_Client, ping_timeout_ms, 1000),

// @Param: _MAX_RETRY
// @DisplayName: DDS ping max attempts
// @Description: The maximum number of times the DDS client will attempt to ping the XRCE agent before exiting.
// @Range: 1 100
// @RebootRequired: True
// @Increment: 1
// @User: Standard
AP_GROUPINFO("_MAX_RETRY", 6, AP_DDS_Client, ping_max_retry, 10),

AP_GROUPEND
};

Expand Down Expand Up @@ -699,9 +718,7 @@ void AP_DDS_Client::main_loop(void)
}

// check ping
const uint64_t ping_timeout_ms{1000};
const uint8_t ping_max_attempts{10};
if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) {
if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_retry)) {
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s No ping response, exiting", msg_prefix);
return;
}
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_DDS/AP_DDS_Client.h
Original file line number Diff line number Diff line change
Expand Up @@ -225,6 +225,12 @@ class AP_DDS_Client
//! @brief ROS_DOMAIN_ID
AP_Int32 domain_id;

//! @brief Timeout in milliseconds when pinging the XRCE agent
AP_Int32 ping_timeout_ms;

//! @brief Maximum number of attempts to ping the XRCE agent before exiting
AP_Int8 ping_max_retry;

//! @brief Enum used to mark a topic as a data reader or writer
enum class Topic_rw : uint8_t {
DataReader = 0,
Expand Down

0 comments on commit a75b8a9

Please sign in to comment.