Skip to content
Snippets Groups Projects
Commit 1c79b1e5 authored by ARMAR-DE's avatar ARMAR-DE
Browse files

Merge remote-tracking branch 'origin/master'

parents 5d37e452 6b85a18e
No related branches found
No related tags found
No related merge requests found
......@@ -29,13 +29,13 @@
namespace armarx
{
inline IceUtil::Time
rtNow()
{
return IceUtil::Time::now(IceUtil::Time::Monotonic);
// using namespace std::chrono;
// auto epoch = time_point_cast<microseconds>(high_resolution_clock::now()).time_since_epoch();
// return IceUtil::Time::microSeconds(duration_cast<milliseconds>(epoch).count());
struct timespec ts;
clock_gettime(CLOCK_MONOTONIC, &ts);
return IceUtil::Time::microSeconds(ts.tv_sec * 1e6 + ts.tv_nsec / 1000);
}
} // namespace armarx
......@@ -43,9 +43,8 @@ namespace armarx
//! \ingroup VirtualTime
//! Prints duration with comment in front of it, yet only once per second.
#define RT_TIMING_END_COMMENT(name, comment) \
ARMARX_RT_LOGF_INFO("%s - duration: %.3f ms", \
comment, \
IceUtil::Time(armarx::rtNow() - name).toMilliSecondsDouble()) \
ARMARX_RT_LOGF_INFO( \
"%s - duration: %.3f ms", comment, (armarx::rtNow() - name).toMilliSecondsDouble()) \
.deactivateSpam(1);
//! \ingroup VirtualTime
//! Prints duration
......@@ -53,7 +52,7 @@ namespace armarx
//! \ingroup VirtualTime
//! Prints duration with comment in front of it if it took longer than threshold
#define RT_TIMING_CEND_COMMENT(name, comment, thresholdMs) \
if ((armarx::rtNow() - name).toMilliSecondsDouble() >= thresholdMs) \
if ((armarx::rtNow() - name).toMicroSeconds() >= thresholdMs) \
RT_TIMING_END_COMMENT(name, comment)
//! \ingroup VirtualTime
//! Prints duration if it took longer than thresholdMs
......
......@@ -65,7 +65,7 @@ namespace armarx::armem::locations::client
if (i)
{
auto loc = i->dataAs<armarx::navigation::location::arondto::Location>();
ret[i->id().entityName] = loc;
ret[i->id().providerSegmentName + "/" + i->id().entityName] = loc;
}
});
return ret;
......@@ -83,6 +83,7 @@ namespace armarx::armem::locations::client
for (auto& [locName, location] : locations)
{
(void) locName;
if (location.framedPose.header.frame == armarx::GlobalFrame)
{
location.framedPose.header.agent = ""; //sanity set
......
......@@ -88,7 +88,13 @@ namespace armarx::armem::obj::instance
auto requestResult = objPoseStorage->requestObjects(req);
return requestResult.results.at(requestObject).result.success;
if (requestResult.results.count(requestObject))
{
return requestResult.results.at(requestObject).result.success;
}
return false;
}
std::optional<objpose::ObjectPose>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment