Skip to content

Commit

Permalink
zero z values in rpp transformed plan (ros-navigation#3066)
Browse files Browse the repository at this point in the history
  • Loading branch information
Aposhian authored and Joshua Wallace committed Dec 14, 2022
1 parent e63eae1 commit 02a8dab
Showing 1 changed file with 1 addition and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -695,6 +695,7 @@ nav_msgs::msg::Path RegulatedPurePursuitController::transformGlobalPlan(
stamped_pose.header.stamp = robot_pose.header.stamp;
stamped_pose.pose = global_plan_pose.pose;
transformPose(costmap_ros_->getBaseFrameID(), stamped_pose, transformed_pose);
transformed_pose.pose.position.z = 0.0;
return transformed_pose;
};

Expand Down

0 comments on commit 02a8dab

Please sign in to comment.