forked from Archive/PX4-Autopilot
dataman: Add client sync perf counter and increase default timeout to 5s
This commit is contained in:
parent
a1cce7e961
commit
23c5c0b12d
|
@ -39,6 +39,8 @@
|
||||||
|
|
||||||
DatamanClient::DatamanClient()
|
DatamanClient::DatamanClient()
|
||||||
{
|
{
|
||||||
|
_sync_perf = perf_alloc(PC_ELAPSED, "DatamanClient: sync");
|
||||||
|
|
||||||
_dataman_request_pub.advertise();
|
_dataman_request_pub.advertise();
|
||||||
_dataman_response_sub = orb_subscribe(ORB_ID(dataman_response));
|
_dataman_response_sub = orb_subscribe(ORB_ID(dataman_response));
|
||||||
|
|
||||||
|
@ -74,6 +76,8 @@ DatamanClient::DatamanClient()
|
||||||
|
|
||||||
DatamanClient::~DatamanClient()
|
DatamanClient::~DatamanClient()
|
||||||
{
|
{
|
||||||
|
perf_free(_sync_perf);
|
||||||
|
|
||||||
if (_dataman_response_sub >= 0) {
|
if (_dataman_response_sub >= 0) {
|
||||||
orb_unsubscribe(_dataman_response_sub);
|
orb_unsubscribe(_dataman_response_sub);
|
||||||
}
|
}
|
||||||
|
@ -85,6 +89,7 @@ bool DatamanClient::syncHandler(const dataman_request_s &request, dataman_respon
|
||||||
bool response_received = false;
|
bool response_received = false;
|
||||||
int32_t ret = 0;
|
int32_t ret = 0;
|
||||||
hrt_abstime time_elapsed = hrt_elapsed_time(&start_time);
|
hrt_abstime time_elapsed = hrt_elapsed_time(&start_time);
|
||||||
|
perf_begin(_sync_perf);
|
||||||
_dataman_request_pub.publish(request);
|
_dataman_request_pub.publish(request);
|
||||||
|
|
||||||
while (!response_received && (time_elapsed < timeout)) {
|
while (!response_received && (time_elapsed < timeout)) {
|
||||||
|
@ -132,6 +137,8 @@ bool DatamanClient::syncHandler(const dataman_request_s &request, dataman_respon
|
||||||
time_elapsed = hrt_elapsed_time(&start_time);
|
time_elapsed = hrt_elapsed_time(&start_time);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
perf_end(_sync_perf);
|
||||||
|
|
||||||
if (!response_received && ret >= 0) {
|
if (!response_received && ret >= 0) {
|
||||||
PX4_ERR("timeout after %" PRIu32 " ms!", static_cast<uint32_t>(timeout / 1000));
|
PX4_ERR("timeout after %" PRIu32 " ms!", static_cast<uint32_t>(timeout / 1000));
|
||||||
}
|
}
|
||||||
|
|
|
@ -62,7 +62,7 @@ public:
|
||||||
*
|
*
|
||||||
* @return true if data was read successfully within the timeout, false otherwise.
|
* @return true if data was read successfully within the timeout, false otherwise.
|
||||||
*/
|
*/
|
||||||
bool readSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 1000_ms);
|
bool readSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 5000_ms);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Write data to the dataman synchronously.
|
* @brief Write data to the dataman synchronously.
|
||||||
|
@ -75,7 +75,7 @@ public:
|
||||||
*
|
*
|
||||||
* @return True if the write operation succeeded, false otherwise.
|
* @return True if the write operation succeeded, false otherwise.
|
||||||
*/
|
*/
|
||||||
bool writeSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 1000_ms);
|
bool writeSync(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 5000_ms);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Clears the data in the specified dataman item.
|
* @brief Clears the data in the specified dataman item.
|
||||||
|
@ -85,7 +85,7 @@ public:
|
||||||
*
|
*
|
||||||
* @return True if the operation was successful, false otherwise.
|
* @return True if the operation was successful, false otherwise.
|
||||||
*/
|
*/
|
||||||
bool clearSync(dm_item_t item, hrt_abstime timeout = 1000_ms);
|
bool clearSync(dm_item_t item, hrt_abstime timeout = 5000_ms);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Initiates an asynchronous request to read the data from dataman for a specific item and index.
|
* @brief Initiates an asynchronous request to read the data from dataman for a specific item and index.
|
||||||
|
@ -185,6 +185,8 @@ private:
|
||||||
|
|
||||||
uint8_t _client_id{0};
|
uint8_t _client_id{0};
|
||||||
|
|
||||||
|
perf_counter_t _sync_perf{nullptr};
|
||||||
|
|
||||||
static constexpr uint8_t CLIENT_ID_NOT_SET{0};
|
static constexpr uint8_t CLIENT_ID_NOT_SET{0};
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -246,7 +248,7 @@ public:
|
||||||
*
|
*
|
||||||
* @return True if the write operation succeeded, false otherwise.
|
* @return True if the write operation succeeded, false otherwise.
|
||||||
*/
|
*/
|
||||||
bool writeWait(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 1000_ms);
|
bool writeWait(dm_item_t item, uint32_t index, uint8_t *buffer, uint32_t length, hrt_abstime timeout = 5000_ms);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Updates the dataman cache by checking for responses from the DatamanClient and processing them.
|
* @brief Updates the dataman cache by checking for responses from the DatamanClient and processing them.
|
||||||
|
|
Loading…
Reference in New Issue