Skip to content

Commit a594e1a

Browse files
YoshiRiStepTurtle
authored andcommitted
fix(probabilistic_occupancy_grid_map): fix robot_pose to refer base_link_frame (autowarefoundation#6485)
fix: fix robot_pose to refer base_link_frame Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 37a205a commit a594e1a

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

perception/probabilistic_occupancy_grid_map/src/pointcloud_based_occupancy_grid_map/pointcloud_based_occupancy_grid_map_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -170,7 +170,7 @@ void PointcloudBasedOccupancyGridMapNode::onPointcloudWithObstacleAndRaw(
170170
Pose gridmap_origin{};
171171
Pose scan_origin{};
172172
try {
173-
robot_pose = utils::getPose(input_raw_msg->header, *tf2_, map_frame_);
173+
robot_pose = utils::getPose(input_raw_msg->header.stamp, *tf2_, base_link_frame_, map_frame_);
174174
gridmap_origin =
175175
utils::getPose(input_raw_msg->header.stamp, *tf2_, gridmap_origin_frame_, map_frame_);
176176
scan_origin =

0 commit comments

Comments
 (0)