Skip to content

Commit 30aed4b

Browse files
committed
fix
Signed-off-by: Tony Najjar <[email protected]>
1 parent 80e0c17 commit 30aed4b

File tree

4 files changed

+5
-5
lines changed

4 files changed

+5
-5
lines changed

nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ void RemoveInCollisionGoals::on_tick()
4848
request_->use_footprint = use_footprint_;
4949

5050
for (const auto & goal : input_goals_.poses) {
51-
request_->poses.poses.push_back(goal);
51+
request_->poses.push_back(goal);
5252
}
5353
}
5454

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -831,7 +831,7 @@ void Costmap2DROS::getCostsCallback(
831831

832832
Costmap2D * costmap = layered_costmap_->getCostmap();
833833
response->success = true;
834-
for (const auto & pose : request->poses.poses) {
834+
for (const auto & pose : request->poses) {
835835
geometry_msgs::msg::PoseStamped pose_transformed;
836836
if (!transformPoseToGlobalFrame(pose, pose_transformed)) {
837837
RCLCPP_ERROR(

nav2_costmap_2d/test/unit/costmap_cost_service_test.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ TEST_F(GetCostServiceTest, TestWithoutFootprint)
5353
geometry_msgs::msg::PoseStamped pose;
5454
pose.pose.position.x = 0.5;
5555
pose.pose.position.y = 1.0;
56-
request->poses.poses.push_back(pose);
56+
request->poses.push_back(pose);
5757
request->use_footprint = false;
5858

5959
auto result_future = client_->async_send_request(request);
@@ -78,7 +78,7 @@ TEST_F(GetCostServiceTest, TestWithFootprint)
7878
tf2::Quaternion q;
7979
q.setRPY(0, 0, 0.5);
8080
pose.pose.orientation = tf2::toMsg(q);
81-
request->poses.poses.push_back(pose);
81+
request->poses.push_back(pose);
8282
request->use_footprint = true;
8383

8484
auto result_future = client_->async_send_request(request);

nav2_rviz_plugins/src/costmap_cost_tool.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ void CostmapCostTool::callCostService(float x, float y)
102102
pose.header.stamp = node->now();
103103
pose.pose.position.x = x;
104104
pose.pose.position.y = y;
105-
request->poses.poses.push_back(pose);
105+
request->poses.push_back(pose);
106106
request->use_footprint = false;
107107

108108
// Call local costmap service

0 commit comments

Comments
 (0)