Skip to content

Commit

Permalink
PSM: Correctly handle full planning scene message (#3610)
Browse files Browse the repository at this point in the history
Fixes #3538/#3609
If the message is not a diff and parent_scene is not set either,
the message should be handled as a full planning scene message as before #3538.
  • Loading branch information
rhaschke authored and sjahr committed Jun 21, 2024
1 parent 9479604 commit e3c20c4
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 1 deletion.
1 change: 1 addition & 0 deletions moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1262,6 +1262,7 @@ bool PlanningScene::setPlanningSceneDiffMsg(const moveit_msgs::msg::PlanningScen

bool PlanningScene::setPlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene_msg)
{
assert(scene_msg.is_diff == false);
RCLCPP_DEBUG(getLogger(), "Setting new planning scene: '%s'", scene_msg.name.c_str());
name_ = scene_msg.name;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -740,7 +740,7 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::Plann
}
else
{
result = scene_->setPlanningSceneDiffMsg(scene);
result = scene_->usePlanningSceneMsg(scene);
}

if (octomap_monitor_)
Expand Down

0 comments on commit e3c20c4

Please sign in to comment.