Skip to content

Commit

Permalink
Fix map display for moving TF frame (#483)
Browse files Browse the repository at this point in the history
Instead of the current time, use Time(0) to get the latest available transform as a fallback.
This is the same logic that is applied in RViz from ROS 1.

Resolves #332

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Jul 20, 2020
1 parent fb6ec8d commit 47b6fcd
Showing 1 changed file with 5 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -547,10 +547,11 @@ void MapDisplay::transformMap()

Ogre::Vector3 position;
Ogre::Quaternion orientation;
if (!context_->getFrameManager()->transform(frame_, transform_time, current_map_.info.origin,
position, orientation) &&
!context_->getFrameManager()->transform(frame_, context_->getClock()->now(),
current_map_.info.origin, position, orientation))
if (!context_->getFrameManager()->transform(
frame_, transform_time, current_map_.info.origin, position, orientation) &&
!context_->getFrameManager()->transform(
frame_, rclcpp::Time(0, 0, context_->getClock()->get_clock_type()),
current_map_.info.origin, position, orientation))
{
setMissingTransformToFixedFrame(frame_);
scene_node_->setVisible(false);
Expand Down

0 comments on commit 47b6fcd

Please sign in to comment.