Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ class VirtualObjectHandler

/// Original object transforms in the base frame
std::vector<tf2::Transform> originalTransforms;
std::vector<std::string> objectFrames;

std::string objectsFrame; ///< Frame in which objects are defined
std::string linkFrame; ///< Link frame where NxLib expects the objects to be defined
Expand Down
7 changes: 4 additions & 3 deletions ensenso_camera/src/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -392,9 +392,10 @@ void Camera::updateGlobalLink(ensenso::ros::Time time, std::string targetFrame,
}
else
{
transformMsg = tfBuffer->lookupTransform(params.linkFrame, targetFrame, time,
ensenso::ros::durationFromSeconds(TF_REQUEST_TIMEOUT));
transformationCache[targetFrame] = transformMsg;
// transformMsg = tfBuffer->lookupTransform(params.linkFrame, targetFrame, time,
// ensenso::ros::durationFromSeconds(TF_REQUEST_TIMEOUT));
transformMsg = tfBuffer->lookupTransform(params.linkFrame, targetFrame, ensenso::ros::Time{0});
transformationCache[targetFrame] = transformMsg;
}
tf2::Transform transform;
tf2::convert(transformMsg.transform, transform);
Expand Down
Loading