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

[ros2] set spin_thread_ to null after delete #27

Open
wants to merge 4 commits into
base: ros2
Choose a base branch
from
Open
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 @@ -190,6 +190,7 @@ class BaseCostmapToPolygons
}
spin_thread_->join();
delete spin_thread_;
spin_thread_ = nullptr;
}

if (spin_thread)
Expand Down Expand Up @@ -225,6 +226,7 @@ class BaseCostmapToPolygons
}
spin_thread_->join();
delete spin_thread_;
spin_thread_ = nullptr;
}
}

Expand All @@ -242,13 +244,15 @@ class BaseCostmapToPolygons
*/
void spinThread()
{
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(nh_);
while (rclcpp::ok())
{
{
std::lock_guard<std::mutex> terminate_lock(terminate_mutex_);
if (need_to_terminate_)
break;
rclcpp::spin_some(nh_);
executor.spin_some();
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#include <pluginlib/class_list_macros.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Vector3.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToDynamicObstacles, costmap_converter::BaseCostmapToPolygons)

Expand Down
20 changes: 10 additions & 10 deletions costmap_converter/test/costmap_polygons.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,10 +122,10 @@ TEST_F(CostmapToPolygonsDBSMCCHTest, dbScan)
std::vector< std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint> > clusters;
costmap_to_polygons.dbScan(clusters);

ASSERT_EQ(3, clusters.size());
ASSERT_EQ(2, clusters[0].size()); // noisy points not belonging to a cluster
ASSERT_EQ(costmap_to_polygons.parameters().max_pts_, clusters[1].size()); // first cluster at (0,0)
ASSERT_EQ(costmap_to_polygons.parameters().max_pts_/2 + 1, clusters[2].size()); // second cluster at (1,1)
ASSERT_EQ((unsigned int)3, clusters.size());
ASSERT_EQ((unsigned int)2, clusters[0].size()); // noisy points not belonging to a cluster
ASSERT_EQ((unsigned int)costmap_to_polygons.parameters().max_pts_, clusters[1].size()); // first cluster at (0,0)
ASSERT_EQ((unsigned int)costmap_to_polygons.parameters().max_pts_/2 + 1, clusters[2].size()); // second cluster at (1,1)
}

TEST(CostmapToPolygonsDBSMCCH, EmptyMap)
Expand All @@ -137,8 +137,8 @@ TEST(CostmapToPolygonsDBSMCCH, EmptyMap)

std::vector< std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint> > clusters;
costmap_to_polygons.dbScan(clusters);
ASSERT_EQ(1, clusters.size()); // noise cluster exists
ASSERT_EQ(0, clusters[0].size()); // noise clsuter is empty
ASSERT_EQ((unsigned int)1, clusters.size()); // noise cluster exists
ASSERT_EQ((unsigned int)0, clusters[0].size()); // noise clsuter is empty
}

TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygon)
Expand All @@ -154,7 +154,7 @@ TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygon)
// degenerate case with just two points
geometry_msgs::msg::Polygon original_polygon = polygon;
costmap_to_polygons.simplifyPolygon(polygon);
ASSERT_EQ(2, polygon.points.size());
ASSERT_EQ((unsigned int)2, polygon.points.size());
for (size_t i = 0; i < polygon.points.size(); ++i)
{
ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x);
Expand All @@ -165,7 +165,7 @@ TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygon)
polygon.points.push_back(create_point(1., simplification_threshold / 2.));
original_polygon = polygon;
costmap_to_polygons.simplifyPolygon(polygon);
ASSERT_EQ(3, polygon.points.size());
ASSERT_EQ((unsigned int)3, polygon.points.size());
for (size_t i = 0; i < polygon.points.size(); ++i)
{
ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x);
Expand All @@ -177,7 +177,7 @@ TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygon)
// remove the point that has to be removed by the simplification
original_polygon.points.erase(original_polygon.points.begin()+2);
costmap_to_polygons.simplifyPolygon(polygon);
ASSERT_EQ(3, polygon.points.size());
ASSERT_EQ((unsigned int)3, polygon.points.size());
for (size_t i = 0; i < polygon.points.size(); ++i)
{
ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x);
Expand Down Expand Up @@ -208,7 +208,7 @@ TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygonPerfectLines)
polygon.points.push_back(create_point(lastPoint.x + i * 1., lastPoint.y));

costmap_to_polygons.simplifyPolygon(polygon);
ASSERT_EQ(6, polygon.points.size());
ASSERT_EQ((unsigned int)6, polygon.points.size());
ASSERT_FLOAT_EQ( 0., polygon.points[0].x);
ASSERT_FLOAT_EQ( 0., polygon.points[0].y);
ASSERT_FLOAT_EQ(100., polygon.points[1].x);
Expand Down