Skip to content

Commit

Permalink
Fixed #1198
Browse files Browse the repository at this point in the history
  • Loading branch information
matlabbe committed Sep 6, 2024
1 parent 18f2788 commit 9deb8a2
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 1 deletion.
2 changes: 2 additions & 0 deletions rtabmap_util/include/rtabmap_util/obstacles_detection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ class ObstaclesDetection : public rclcpp::Node
rtabmap::LocalGridMaker localMapMaker_;
bool mapFrameProjection_;
bool warned_;
float rangeMin_;
float rangeMax_;

std::shared_ptr<tf2_ros::Buffer> tfBuffer_;
std::shared_ptr<tf2_ros::TransformListener> tfListener_;
Expand Down
47 changes: 46 additions & 1 deletion rtabmap_util/src/nodelets/obstacles_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,9 @@ ObstaclesDetection::ObstaclesDetection(const rclcpp::NodeOptions & options) :
frameId_("base_link"),
waitForTransform_(0.2),
mapFrameProjection_(rtabmap::Parameters::defaultGridMapFrameProjection()),
warned_(false)
warned_(false),
rangeMin_(0),
rangeMax_(0)
{
ULogger::setType(ULogger::kTypeConsole);
ULogger::setLevel(ULogger::kWarning);
Expand Down Expand Up @@ -75,6 +77,8 @@ ObstaclesDetection::ObstaclesDetection(const rclcpp::NodeOptions & options) :
}

localMapMaker_.parseParameters(gridParameters);
rtabmap::Parameters::parse(gridParameters, rtabmap::Parameters::kGridRangeMin(), rangeMin_);
rtabmap::Parameters::parse(gridParameters, rtabmap::Parameters::kGridRangeMax(), rangeMax_);

tfBuffer_ = std::make_shared< tf2_ros::Buffer >(this->get_clock());
tfListener_ = std::make_shared< tf2_ros::TransformListener >(*tfBuffer_);
Expand All @@ -86,6 +90,42 @@ ObstaclesDetection::ObstaclesDetection(const rclcpp::NodeOptions & options) :
cloudSub_ = create_subscription<sensor_msgs::msg::PointCloud2>("cloud", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)qos), std::bind(&ObstaclesDetection::callback, this, std::placeholders::_1));
}

pcl::PointCloud<pcl::PointXYZ> rangeFiltering(
const pcl::PointCloud<pcl::PointXYZ> & cloud,
float rangeMin,
float rangeMax)
{
if(!cloud.empty() && (rangeMin > 0.0f || rangeMax > 0.0f))
{
pcl::PointCloud<pcl::PointXYZ> output;
output.reserve(cloud.size());
int oi = 0;
float rangeMinSqrd = rangeMin * rangeMin;
float rangeMaxSqrd = rangeMax * rangeMax;
for(size_t i=0; i<cloud.size(); ++i)
{
const pcl::PointXYZ & pt = cloud.at(i);
float r = pt.x*pt.x + pt.y*pt.y + pt.z*pt.z;

if(rangeMin > 0.0f && r < rangeMinSqrd)
{
continue;
}
if(rangeMax > 0.0f && r > rangeMaxSqrd)
{
continue;
}

output.push_back(pt);
++oi;
}
output.resize(oi);
return output;
}

return cloud;
}

void ObstaclesDetection::callback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr cloudMsg)
{
rclcpp::Time time = now();
Expand Down Expand Up @@ -137,6 +177,11 @@ void ObstaclesDetection::callback(const sensor_msgs::msg::PointCloud2::ConstShar
inputCloud->is_dense = true;
}

if(rangeMin_ > 0.0f || rangeMax_ > 0.0f)
{
*inputCloud = rangeFiltering(*inputCloud, rangeMin_, rangeMax_);
}

//Common variables for all strategies
pcl::IndicesPtr ground, obstacles;
pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(new pcl::PointCloud<pcl::PointXYZ>);
Expand Down

0 comments on commit 9deb8a2

Please sign in to comment.