Skip to content

Commit

Permalink
Merge pull request #1696 from tier4/hotfix/v3.0.3/surround-obstacle-c…
Browse files Browse the repository at this point in the history
…hecker-tf

fix(surround_obstacle_checker): use tf2::TimePointZero
  • Loading branch information
saka1-s authored Dec 12, 2024
2 parents f8fed79 + 1479b91 commit b85ee97
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,7 @@ class SurroundObstacleCheckerNode : public rclcpp::Node
std::optional<Obstacle> getNearestObstacleByDynamicObject() const;

std::optional<geometry_msgs::msg::TransformStamped> getTransform(
const std::string & source, const std::string & target, const rclcpp::Time & stamp,
double duration_sec) const;
const std::string & source, const std::string & target) const;

bool isStopRequired(const bool is_obstacle_found, const bool is_stopped);

Expand Down
12 changes: 4 additions & 8 deletions planning/surround_obstacle_checker/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -424,8 +424,7 @@ std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacleByPointCl
return std::nullopt;
}

const auto transform_stamped =
getTransform("base_link", pointcloud_ptr_->header.frame_id, pointcloud_ptr_->header.stamp, 0.5);
const auto transform_stamped = getTransform("base_link", pointcloud_ptr_->header.frame_id);

if (!transform_stamped) {
return std::nullopt;
Expand Down Expand Up @@ -468,8 +467,7 @@ std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacleByDynamic
{
if (!object_ptr_ || !use_dynamic_object_) return std::nullopt;

const auto transform_stamped =
getTransform(object_ptr_->header.frame_id, "base_link", object_ptr_->header.stamp, 0.5);
const auto transform_stamped = getTransform(object_ptr_->header.frame_id, "base_link");

if (!transform_stamped) {
return std::nullopt;
Expand Down Expand Up @@ -522,14 +520,12 @@ std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacleByDynamic
}

std::optional<geometry_msgs::msg::TransformStamped> SurroundObstacleCheckerNode::getTransform(
const std::string & source, const std::string & target, const rclcpp::Time & stamp,
double duration_sec) const
const std::string & source, const std::string & target) const
{
geometry_msgs::msg::TransformStamped transform_stamped;

try {
transform_stamped =
tf_buffer_.lookupTransform(source, target, stamp, tf2::durationFromSec(duration_sec));
transform_stamped = tf_buffer_.lookupTransform(source, target, tf2::TimePointZero);
} catch (tf2::TransformException & ex) {
return {};
}
Expand Down

0 comments on commit b85ee97

Please sign in to comment.