Skip to content

Commit

Permalink
[uxrce-dds-client]: add parameter to disable time synchronization bet…
Browse files Browse the repository at this point in the history
…ween Agent and Client

Signed-off-by: Beniamino Pozzan <[email protected]>
  • Loading branch information
beniaminopozzan authored Jul 26, 2023
1 parent 56b59dc commit b9667e9
Show file tree
Hide file tree
Showing 3 changed files with 40 additions and 7 deletions.
11 changes: 11 additions & 0 deletions src/modules/uxrce_dds_client/module.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -64,3 +64,14 @@ parameters:
reboot_required: true
default: 2130706433
requires_ethernet: true

UXRCE_DDS_SYNCT:
description:
short: uXRCE-DDS timestamp synchronization enable
long: When enabled, uxrce_dds_client will synchronize the timestamps
of the incoming and outgoing messages measuring the offset
between the Agent OS time and the PX4 time.
type: boolean
category: System
reboot_required: true
default: 1
33 changes: 27 additions & 6 deletions src/modules/uxrce_dds_client/uxrce_dds_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,11 +79,18 @@ void on_time(uxrSession *session, int64_t current_time, int64_t received_timesta
}
}

void on_time_no_sync(uxrSession *session, int64_t current_time, int64_t received_timestamp, int64_t transmit_timestamp,
int64_t originate_timestamp, void *args)
{
session->time_offset = 0;
}

UxrceddsClient::UxrceddsClient(Transport transport, const char *device, int baudrate, const char *agent_ip,
const char *port, bool localhost_only, bool custom_participant, const char *client_namespace) :
const char *port, bool localhost_only, bool custom_participant, const char *client_namespace,
bool synchronize_timestamps) :
ModuleParams(nullptr),
_localhost_only(localhost_only), _custom_participant(custom_participant),
_client_namespace(client_namespace)
_client_namespace(client_namespace), _synchronize_timestamps(synchronize_timestamps)
{
if (transport == Transport::Serial) {

Expand Down Expand Up @@ -299,12 +306,17 @@ void UxrceddsClient::run()
_connected = true;

// Set time-callback.
uxr_set_time_callback(&session, on_time, &_timesync);
if (_synchronize_timestamps) {
uxr_set_time_callback(&session, on_time, &_timesync);

} else {
uxr_set_time_callback(&session, on_time_no_sync, nullptr);
}

// Synchronize with the Agent
bool synchronized = false;

while (!synchronized) {
while (_synchronize_timestamps && !synchronized) {
synchronized = uxr_sync_session(&session, 1000);

if (synchronized) {
Expand All @@ -331,7 +343,7 @@ void UxrceddsClient::run()
uxr_run_session_timeout(&session, 0);

// time sync session
if (hrt_elapsed_time(&last_sync_session) > 1_s) {
if (_synchronize_timestamps && hrt_elapsed_time(&last_sync_session) > 1_s) {
if (uxr_sync_session(&session, 100)) {
//PX4_INFO("synchronized with time offset %-5" PRId64 "ns", session.time_offset);
last_sync_session = hrt_absolute_time();
Expand Down Expand Up @@ -694,8 +706,17 @@ UxrceddsClient *UxrceddsClient::instantiate(int argc, char *argv[])
}
}

// determines if timestamps should be synchronized
int32_t synchronize_timestamps = 0;
param_get(param_find("UXRCE_DDS_SYNCT"), &synchronize_timestamps);

if ((synchronize_timestamps != 1) && (synchronize_timestamps != 0)) {
PX4_ERR("UXRCE_DDS_SYNCT must be either 0 or 1");
}


return new UxrceddsClient(transport, device, baudrate, agent_ip, port, localhost_only, custom_participant,
client_namespace);
client_namespace, synchronize_timestamps);
}

int UxrceddsClient::print_usage(const char *reason)
Expand Down
3 changes: 2 additions & 1 deletion src/modules/uxrce_dds_client/uxrce_dds_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class UxrceddsClient : public ModuleBase<UxrceddsClient>, public ModuleParams
};

UxrceddsClient(Transport transport, const char *device, int baudrate, const char *host, const char *port,
bool localhost_only, bool custom_participant, const char *client_namespace);
bool localhost_only, bool custom_participant, const char *client_namespace, bool synchornize_timestamps);

~UxrceddsClient();

Expand Down Expand Up @@ -77,6 +77,7 @@ class UxrceddsClient : public ModuleBase<UxrceddsClient>, public ModuleParams
const bool _localhost_only;
const bool _custom_participant;
const char *_client_namespace;
const bool _synchronize_timestamps;


// max port characters (5+'\0')
Expand Down

0 comments on commit b9667e9

Please sign in to comment.