Skip to content
Merged
Changes from 1 commit
Commits
Show all changes
37 commits
Select commit Hold shift + click to select a range
0534487
Adding launch_testing_ros dep on nav2 utils to install (#2450)
SteveMacenski Jul 14, 2021
c1b506e
Reduce map saver nodes (#2454)
gezp Jul 21, 2021
6151f13
Update nav2_controller.cpp (#2462)
harderthan Jul 21, 2021
5618b02
Reduce lifecycle manager nodes (#2456)
gezp Jul 22, 2021
c9af557
sync with main and use ros_diff_drive in case name changes (#2472)
Yousseflah Jul 23, 2021
5ab9386
Nav2 Simple (Python3) Commander Library (#2411)
SteveMacenski Jun 18, 2021
65f8d74
Python string format (#2466)
Timple Jul 23, 2021
f116316
Fix Smac cleanup (#2477)
doisyg Jul 26, 2021
d028caa
Naming BT client node after action name (#2470)
anaelle-sw Jul 26, 2021
27c285b
fix nav2 params and launch file to publish Local and global costmaps …
Yousseflah Jul 26, 2021
da4f972
[SmacPlanner2D] make tolerance parameter dynamic (#2475)
doisyg Aug 2, 2021
0748913
Modify the BtServiceNode to include an on_success call. (#2481)
philison Aug 4, 2021
826b0d0
Accept path of length 1 (#2495)
doisyg Aug 9, 2021
ea90f46
Fix null pointer in amcl on_cleanup (#2503)
zouyonghao Aug 12, 2021
b33e382
fix data race: addPlugin() and resizeMap() can be executed concurrent…
easylyou Aug 16, 2021
e326d3f
fix data race: VoxelLayer::matchSize may be executed concurrently (#2…
easylyou Aug 16, 2021
8316fa2
catch runtime_error if the message from laser is malformed (#2511)
easylyou Aug 17, 2021
2acd470
Smac planner bad alloc (#2516)
Aposhian Aug 17, 2021
5c5fc77
[ObstacleLayer] Use message_filter timeout (#2518)
doisyg Aug 17, 2021
05e6029
fix possible use-after-free: unsafe shared_ptr in multithread (#2510)
easylyou Aug 19, 2021
cbfe97e
fix export dependency and library (#2521)
gezp Aug 19, 2021
9dab8be
Add more semantic checks for amcl parameters (#2528)
zouyonghao Aug 24, 2021
58f59bf
fix possible use-after-free: unsafe shared_ptr in multithread (#2530)
easylyou Aug 24, 2021
9e342e4
Hot fix rrp slow (#2526)
padhupradheep Aug 24, 2021
168a92d
Fix out of voxel grid array regression (#2460)
AlexeyMerzlyakov Aug 25, 2021
88b98e7
Update dwb_local_planner.hpp (#2533)
harderthan Aug 25, 2021
bb3789b
Add new test for smac_planner_2d (#2531)
lucabonamini Aug 25, 2021
ec95d2d
Fix linting issue introduced in https://github.com/ros-planning/navig…
SteveMacenski Aug 27, 2021
b6194b2
[All 2D planners] Fix last pose orientation, fix small path and add i…
doisyg Sep 1, 2021
d9983a5
Use worldToMapEnforceBounds in clear_costmap_service (#2544)
zouyonghao Sep 1, 2021
8088162
Add new test for nav2_regulated_pure_pursuit (#2542)
sathak93 Sep 4, 2021
6ce9462
Enabled runtime configuration of parameters for Hybrid A* (#2540)
lucabonamini Sep 4, 2021
f4b65b0
fix pf_ use-before-initial in laserReceived() callback (#2550)
easylyou Sep 7, 2021
87dfb3c
add semantic checks (#2557)
easylyou Sep 11, 2021
b3331a8
bumping galactic to 1.0.7
SteveMacenski Sep 14, 2021
0e59580
Updates to Nav2 Theta Star Planner docs (#2559)
Anshu-man567 Sep 15, 2021
2eb6e0f
Fixed vector::reserve exception in smac planner due to precision erro…
zoltan-lengyel Sep 15, 2021
File filter

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
fix possible use-after-free: unsafe shared_ptr in multithread (#2510)
Co-authored-by: Kai-Tao Xie <kaitaoxie@qq.com>
  • Loading branch information
2 people authored and SteveMacenski committed Sep 14, 2021
commit 05e60294cf55a457b528b991b897ef5ac2280680
7 changes: 4 additions & 3 deletions nav2_costmap_2d/src/footprint_subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,10 @@ FootprintSubscriber::getFootprint(
return false;
}

auto current_footprint = std::atomic_load(&footprint_);
footprint = toPointVector(
std::make_shared<geometry_msgs::msg::Polygon>(footprint_->polygon));
auto & footprint_stamp = footprint_->header.stamp;
std::make_shared<geometry_msgs::msg::Polygon>(current_footprint->polygon));
auto & footprint_stamp = current_footprint->header.stamp;

if (stamp - footprint_stamp > valid_footprint_timeout) {
return false;
Expand Down Expand Up @@ -89,7 +90,7 @@ FootprintSubscriber::getFootprint(
void
FootprintSubscriber::footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg)
{
footprint_ = msg;
std::atomic_store(&footprint_, msg);
if (!footprint_received_) {
footprint_received_ = true;
}
Expand Down