Skip to content

Commit

Permalink
Switch from ROS_TIME to SYSTEM_TIME on rclcpp::Time construction (#1117)
Browse files Browse the repository at this point in the history
This prevents a std::runtime_exception due to differing clock types
between default constructed rclcpp::Time object and an explicitly
constructed rclcpp::Time object constructed from a msg::Time object
using a ROS_TIME clock type

Co-authored-by: austin.moore <[email protected]>
  • Loading branch information
1 parent 95552e4 commit 30b471a
Showing 1 changed file with 2 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ void InteractiveMarker::processMessage(

reference_time_ = rclcpp::Time(message.header.stamp, RCL_ROS_TIME);
reference_frame_ = message.header.frame_id;
frame_locked_ = (reference_time_ == rclcpp::Time());
frame_locked_ = (message.header.stamp == builtin_interfaces::msg::Time());

requestPoseUpdate(position, orientation);
context_->queueRender();
Expand All @@ -122,7 +122,7 @@ bool InteractiveMarker::processMessage(const visualization_msgs::msg::Interactiv

reference_time_ = rclcpp::Time(message.header.stamp, RCL_ROS_TIME);
reference_frame_ = message.header.frame_id;
frame_locked_ = (reference_time_ == rclcpp::Time());
frame_locked_ = (message.header.stamp == builtin_interfaces::msg::Time());

position_ = Ogre::Vector3(
message.pose.position.x, message.pose.position.y, message.pose.position.z);
Expand Down

0 comments on commit 30b471a

Please sign in to comment.