Skip to content

Commit 4bcbac7

Browse files
[PSM] Process collision object color when adding object trough the planning scene monitor (#2567)
* Added an optional Collision Object color object to set the coller of the collision object when adding the collision object trough the PSM. * Fixes for clang-tidy warnings * fix pre-commit * Pass by reference
1 parent 0d2d070 commit 4bcbac7

File tree

4 files changed

+14
-4
lines changed

4 files changed

+14
-4
lines changed

moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,10 +42,15 @@ namespace bind_planning_scene_monitor
4242
{
4343

4444
bool processCollisionObject(const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
45-
moveit_msgs::msg::CollisionObject& collision_object_msg)
45+
moveit_msgs::msg::CollisionObject& collision_object_msg,
46+
std::optional<moveit_msgs::msg::ObjectColor> color_msg)
4647
{
4748
moveit_msgs::msg::CollisionObject::ConstSharedPtr const_ptr =
4849
std::make_shared<const moveit_msgs::msg::CollisionObject>(collision_object_msg);
50+
if (color_msg)
51+
{
52+
return planning_scene_monitor->processCollisionObjectMsg(const_ptr, *std::move(color_msg));
53+
}
4954
return planning_scene_monitor->processCollisionObjectMsg(const_ptr);
5055
}
5156

@@ -153,7 +158,7 @@ void initPlanningSceneMonitor(py::module& m)
153158
Clears the octomap.
154159
)")
155160
.def("process_collision_object", &moveit_py::bind_planning_scene_monitor::processCollisionObject,
156-
py::arg("collision_object_msg"), // py::arg("color_msg") = nullptr,
161+
py::arg("collision_object_msg"), py::arg("color_msg") = nullptr,
157162
R"(
158163
Apply a collision object to the planning scene.
159164

moveit_py/src/moveit/moveit_ros/planning_scene_monitor/planning_scene_monitor.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
#pragma once
3838

3939
#include <pybind11/pybind11.h>
40+
#include <pybind11/stl.h>
4041
#include <moveit_py/moveit_py_utils/copy_ros_msg.h>
4142
#include <moveit_py/moveit_py_utils/ros_msg_typecasters.h>
4243
#include <rclcpp/rclcpp.hpp>

moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -393,7 +393,8 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor
393393
bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene& scene);
394394

395395
// Called to update a collision object in the planning scene.
396-
bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& collision_object_msg);
396+
bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& collision_object_msg,
397+
const std::optional<moveit_msgs::msg::ObjectColor>& color_msg = std::nullopt);
397398

398399
// Called to update an attached collision object in the planning scene.
399400
bool processAttachedCollisionObjectMsg(

moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -780,7 +780,8 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::Plann
780780
return result;
781781
}
782782

783-
bool PlanningSceneMonitor::processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& object)
783+
bool PlanningSceneMonitor::processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& object,
784+
const std::optional<moveit_msgs::msg::ObjectColor>& color_msg)
784785
{
785786
if (!scene_)
786787
return false;
@@ -791,6 +792,8 @@ bool PlanningSceneMonitor::processCollisionObjectMsg(const moveit_msgs::msg::Col
791792
last_update_time_ = rclcpp::Clock().now();
792793
if (!scene_->processCollisionObjectMsg(*object))
793794
return false;
795+
if (color_msg.has_value())
796+
scene_->setObjectColor(color_msg.value().id, color_msg.value().color);
794797
}
795798
triggerSceneUpdateEvent(UPDATE_GEOMETRY);
796799
RCLCPP_INFO(logger_, "Published update collision object");

0 commit comments

Comments
 (0)