Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[PSM] Process collision object color when adding object trough the planning scene monitor #2567

Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,15 @@ namespace bind_planning_scene_monitor
{

bool processCollisionObject(const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
moveit_msgs::msg::CollisionObject& collision_object_msg)
moveit_msgs::msg::CollisionObject& collision_object_msg,
std::optional<moveit_msgs::msg::ObjectColor> color_msg)
{
moveit_msgs::msg::CollisionObject::ConstSharedPtr const_ptr =
std::make_shared<const moveit_msgs::msg::CollisionObject>(collision_object_msg);
if (color_msg)
{
return planning_scene_monitor->processCollisionObjectMsg(const_ptr, *std::move(color_msg));
}
return planning_scene_monitor->processCollisionObjectMsg(const_ptr);
}

Expand Down Expand Up @@ -153,7 +158,7 @@ void initPlanningSceneMonitor(py::module& m)
Clears the octomap.
)")
.def("process_collision_object", &moveit_py::bind_planning_scene_monitor::processCollisionObject,
py::arg("collision_object_msg"), // py::arg("color_msg") = nullptr,
py::arg("collision_object_msg"), py::arg("color_msg") = nullptr,
R"(
Apply a collision object to the planning scene.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#pragma once

#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
#include <moveit_py/moveit_py_utils/copy_ros_msg.h>
#include <moveit_py/moveit_py_utils/ros_msg_typecasters.h>
#include <rclcpp/rclcpp.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -393,7 +393,8 @@ class MOVEIT_PLANNING_SCENE_MONITOR_EXPORT PlanningSceneMonitor
bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene& scene);

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

// Called to update an attached collision object in the planning scene.
bool processAttachedCollisionObjectMsg(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -780,7 +780,8 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::msg::Plann
return result;
}

bool PlanningSceneMonitor::processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& object)
bool PlanningSceneMonitor::processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject::ConstSharedPtr& object,
const std::optional<moveit_msgs::msg::ObjectColor>& color_msg)
{
if (!scene_)
return false;
Expand All @@ -791,6 +792,8 @@ bool PlanningSceneMonitor::processCollisionObjectMsg(const moveit_msgs::msg::Col
last_update_time_ = rclcpp::Clock().now();
if (!scene_->processCollisionObjectMsg(*object))
return false;
if (color_msg.has_value())
scene_->setObjectColor(color_msg.value().id, color_msg.value().color);
}
triggerSceneUpdateEvent(UPDATE_GEOMETRY);
RCLCPP_INFO(logger_, "Published update collision object");
Expand Down
Loading