Skip to content

Commit

Permalink
Add asserts to setPlanningScene*Msg()
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Jun 20, 2024
1 parent 5b10e4c commit 617f17e
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1264,6 +1264,7 @@ void PlanningScene::decoupleParent()

bool PlanningScene::setPlanningSceneDiffMsg(const moveit_msgs::PlanningScene& scene_msg)
{
assert(scene_msg.is_diff == true);
bool result = true;

ROS_DEBUG_NAMED(LOGNAME, "Adding planning scene diff");
Expand Down Expand Up @@ -1318,6 +1319,7 @@ bool PlanningScene::setPlanningSceneDiffMsg(const moveit_msgs::PlanningScene& sc

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

Expand Down

0 comments on commit 617f17e

Please sign in to comment.