Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(behavior_velocity): add mutex for points subscription #1125

Merged
merged 1 commit into from
Jun 20, 2022
Merged
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 @@ -96,7 +96,7 @@ class DynamicObstacleCreator
public:
explicit DynamicObstacleCreator(rclcpp::Node & node) : node_(node) {}
virtual ~DynamicObstacleCreator() = default;
virtual std::vector<DynamicObstacle> createDynamicObstacles() const = 0;
virtual std::vector<DynamicObstacle> createDynamicObstacles() = 0;
void setParam(const DynamicObstacleParam & param) { param_ = param; }
void setData(const PlannerData & planner_data, const PathWithLaneId & path)
{
Expand All @@ -118,7 +118,7 @@ class DynamicObstacleCreatorForObject : public DynamicObstacleCreator
{
public:
explicit DynamicObstacleCreatorForObject(rclcpp::Node & node);
std::vector<DynamicObstacle> createDynamicObstacles() const override;
std::vector<DynamicObstacle> createDynamicObstacles() override;
};

/**
Expand All @@ -129,7 +129,7 @@ class DynamicObstacleCreatorForObjectWithoutPath : public DynamicObstacleCreator
{
public:
explicit DynamicObstacleCreatorForObjectWithoutPath(rclcpp::Node & node);
std::vector<DynamicObstacle> createDynamicObstacles() const override;
std::vector<DynamicObstacle> createDynamicObstacles() override;
};

/**
Expand All @@ -140,7 +140,7 @@ class DynamicObstacleCreatorForPoints : public DynamicObstacleCreator
{
public:
explicit DynamicObstacleCreatorForPoints(rclcpp::Node & node);
std::vector<DynamicObstacle> createDynamicObstacles() const override;
std::vector<DynamicObstacle> createDynamicObstacles() override;

private:
void onCompareMapFilteredPointCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg);
Expand All @@ -150,6 +150,9 @@ class DynamicObstacleCreatorForPoints : public DynamicObstacleCreator
// tf
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

// mutex for compare_map_filtered_pointcloud
std::mutex mutex_;
};

} // namespace behavior_velocity_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ DynamicObstacleCreatorForObject::DynamicObstacleCreatorForObject(rclcpp::Node &
{
}

std::vector<DynamicObstacle> DynamicObstacleCreatorForObject::createDynamicObstacles() const
std::vector<DynamicObstacle> DynamicObstacleCreatorForObject::createDynamicObstacles()
{
// create dynamic obstacles from predicted objects
std::vector<DynamicObstacle> dynamic_obstacles;
Expand Down Expand Up @@ -115,7 +115,6 @@ DynamicObstacleCreatorForObjectWithoutPath::DynamicObstacleCreatorForObjectWitho
}

std::vector<DynamicObstacle> DynamicObstacleCreatorForObjectWithoutPath::createDynamicObstacles()
const
{
std::vector<DynamicObstacle> dynamic_obstacles;

Expand Down Expand Up @@ -154,8 +153,9 @@ DynamicObstacleCreatorForPoints::DynamicObstacleCreatorForPoints(rclcpp::Node &
std::bind(&DynamicObstacleCreatorForPoints::onCompareMapFilteredPointCloud, this, _1));
}

std::vector<DynamicObstacle> DynamicObstacleCreatorForPoints::createDynamicObstacles() const
std::vector<DynamicObstacle> DynamicObstacleCreatorForPoints::createDynamicObstacles()
{
std::lock_guard<std::mutex> lock(mutex_);
std::vector<DynamicObstacle> dynamic_obstacles;
for (const auto & point : dynamic_obstacle_data_.compare_map_filtered_pointcloud) {
DynamicObstacle dynamic_obstacle;
Expand Down Expand Up @@ -213,6 +213,7 @@ void DynamicObstacleCreatorForPoints::onCompareMapFilteredPointCloud(
pcl::PointCloud<pcl::PointXYZ>::Ptr pc_transformed(new pcl::PointCloud<pcl::PointXYZ>);
pcl::transformPointCloud(pc, *pc_transformed, affine);

std::lock_guard<std::mutex> lock(mutex_);
dynamic_obstacle_data_.compare_map_filtered_pointcloud = applyVoxelGridFilter(pc_transformed);
}
} // namespace behavior_velocity_planner