Skip to content

Commit

Permalink
Merge pull request moveit#3538 from v4hn/keep-monitoring-same-scene-o…
Browse files Browse the repository at this point in the history
…bject

PSM: keep references to scene_ valid upon receiving full scenes
  • Loading branch information
v4hn authored Feb 8, 2024
2 parents 95dd7fb + c174715 commit 8f39ef7
Show file tree
Hide file tree
Showing 4 changed files with 167 additions and 18 deletions.
3 changes: 3 additions & 0 deletions moveit_ros/planning/planning_scene_monitor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@ if (CATKIN_ENABLE_TESTING)

add_rostest_gtest(current_state_monitor_test test/current_state_monitor.test test/current_state_monitor_test.cpp)
target_link_libraries(current_state_monitor_test ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES})

add_rostest_gtest(planning_scene_monitor_test test/planning_scene_monitor.test test/planning_scene_monitor_test.cpp)
target_link_libraries(planning_scene_monitor_test ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES})
endif()

install(TARGETS ${MOVEIT_LIB_NAME}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -580,7 +580,21 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningSc
"scene update " << fmod(last_update_time_.toSec(), 10.)
<< " robot stamp: " << fmod(last_robot_motion_time_.toSec(), 10.));
old_scene_name = scene_->getName();
result = scene_->usePlanningSceneMsg(scene);

if (!scene.is_diff && parent_scene_)
{
// clear maintained (diff) scene_ and set the full new scene in parent_scene_ instead
scene_->clearDiffs();
result = parent_scene_->setPlanningSceneMsg(scene);
// There were no callbacks for individual object changes, so rebuild the octree masks
excludeAttachedBodiesFromOctree();
excludeWorldObjectsFromOctree();
}
else
{
result = scene_->setPlanningSceneDiffMsg(scene);
}

if (octomap_monitor_)
{
if (!scene.is_diff && scene.world.octomap.octomap.data.empty())
Expand All @@ -592,23 +606,6 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningSc
}
robot_model_ = scene_->getRobotModel();

// if we just reset the scene completely but we were maintaining diffs, we need to fix that
if (!scene.is_diff && parent_scene_)
{
// the scene is now decoupled from the parent, since we just reset it
scene_->setAttachedBodyUpdateCallback(moveit::core::AttachedBodyCallback());
scene_->setCollisionObjectUpdateCallback(collision_detection::World::ObserverCallbackFn());
parent_scene_ = scene_;
scene_ = parent_scene_->diff();
scene_const_ = scene_;
scene_->setAttachedBodyUpdateCallback([this](moveit::core::AttachedBody* body, bool attached) {
currentStateAttachedBodyUpdateCallback(body, attached);
});
scene_->setCollisionObjectUpdateCallback(
[this](const collision_detection::World::ObjectConstPtr& object, collision_detection::World::Action action) {
currentWorldObjectUpdateCallback(object, action);
});
}
if (octomap_monitor_)
{
excludeAttachedBodiesFromOctree(); // in case updates have happened to the attached bodies, put them in
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<include file="$(find moveit_resources_fanuc_moveit_config)/launch/planning_context.launch">
<arg name="load_robot_description" value="true"/>
</include>

<test test-name="planning_scene_monitor_test" pkg="moveit_ros_planning" type="planning_scene_monitor_test" />
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2023, University of Hamburg
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Michael 'v4hn' Goerner
Desc: Tests for PlanningSceneMonitor
*/

// ROS
#include <ros/ros.h>

// Testing
#include <gtest/gtest.h>

// Main class
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/robot_state/conversions.h>

class PlanningSceneMonitorTest : public ::testing::Test
{
public:
void SetUp() override
{
psm = std::make_unique<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
psm->monitorDiffs(true);
scene = psm->getPlanningScene();
}

void TearDown() override
{
scene.reset();
}

protected:
planning_scene_monitor::PlanningSceneMonitorPtr psm;
planning_scene::PlanningScenePtr scene;
};

// various code expects the monitored scene to remain the same
TEST_F(PlanningSceneMonitorTest, TestPersistentScene)
{
auto scene{ psm->getPlanningScene() };
moveit_msgs::PlanningScene msg;
msg.is_diff = msg.robot_state.is_diff = true;
psm->newPlanningSceneMessage(msg);
EXPECT_EQ(scene, psm->getPlanningScene());

msg.is_diff = msg.robot_state.is_diff = false;
psm->newPlanningSceneMessage(msg);
EXPECT_EQ(scene, psm->getPlanningScene());
}

using UpdateType = planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType;

#define TRIGGERS_UPDATE(msg, expected_update_type) \
{ \
psm->clearUpdateCallbacks(); \
auto received_update_type{ UpdateType::UPDATE_NONE }; \
psm->addUpdateCallback([&](auto type) { received_update_type = type; }); \
psm->newPlanningSceneMessage(msg); \
EXPECT_EQ(received_update_type, expected_update_type); \
}

TEST_F(PlanningSceneMonitorTest, UpdateTypes)
{
moveit_msgs::PlanningScene msg;
msg.is_diff = msg.robot_state.is_diff = true;
TRIGGERS_UPDATE(msg, UpdateType::UPDATE_NONE);

msg.fixed_frame_transforms.emplace_back();
msg.fixed_frame_transforms.back().header.frame_id = "base_link";
msg.fixed_frame_transforms.back().child_frame_id = "object";
msg.fixed_frame_transforms.back().transform.rotation.w = 1.0;
TRIGGERS_UPDATE(msg, UpdateType::UPDATE_TRANSFORMS);
msg.fixed_frame_transforms.clear();

moveit::core::robotStateToRobotStateMsg(scene->getCurrentState(), msg.robot_state, false);
msg.robot_state.is_diff = true;
TRIGGERS_UPDATE(msg, UpdateType::UPDATE_STATE);

msg.robot_state.is_diff = false;
TRIGGERS_UPDATE(msg, UpdateType::UPDATE_STATE | UpdateType::UPDATE_GEOMETRY);

msg.robot_state = moveit_msgs::RobotState{};
msg.robot_state.is_diff = true;
moveit_msgs::CollisionObject co;
co.header.frame_id = "base_link";
co.id = "object";
co.operation = moveit_msgs::CollisionObject::ADD;
co.pose.orientation.w = 1.0;
co.primitives.emplace_back();
co.primitives.back().type = shape_msgs::SolidPrimitive::SPHERE;
co.primitives.back().dimensions = { 1.0 };
msg.world.collision_objects.emplace_back(co);
TRIGGERS_UPDATE(msg, UpdateType::UPDATE_GEOMETRY);

msg.world.collision_objects.clear();
msg.is_diff = false;

TRIGGERS_UPDATE(msg, UpdateType::UPDATE_SCENE);
}

int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "planning_scene_monitor_test");

// ros::AsyncSpinner spinner{ 1 };
// spinner.start();

return RUN_ALL_TESTS();
}

0 comments on commit 8f39ef7

Please sign in to comment.