41 #include <moveit_msgs/srv/get_planning_scene.hpp>
43 #include <tf2/exceptions.h>
44 #include <tf2/LinearMath/Transform.h>
45 #include <tf2_eigen/tf2_eigen.hpp>
46 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
48 #include <boost/algorithm/string/join.hpp>
51 #include <std_msgs/msg/string.hpp>
54 using namespace std::chrono_literals;
56 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.planning_scene_monitor.planning_scene_monitor");
60 const std::string PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC =
"joint_states";
61 const std::string PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC =
"attached_collision_object";
62 const std::string PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC =
"collision_object";
63 const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC =
"planning_scene_world";
64 const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC =
"planning_scene";
65 const std::string PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_SERVICE =
"get_planning_scene";
66 const std::string PlanningSceneMonitor::MONITORED_PLANNING_SCENE_TOPIC =
"monitored_planning_scene";
68 PlanningSceneMonitor::PlanningSceneMonitor(
const rclcpp::Node::SharedPtr& node,
const std::string& robot_description,
69 const std::string&
name)
75 const planning_scene::PlanningScenePtr&
scene,
76 const std::string& robot_description,
const std::string&
name)
83 const robot_model_loader::RobotModelLoaderPtr& rm_loader,
84 const std::string&
name)
90 const planning_scene::PlanningScenePtr&
scene,
91 const robot_model_loader::RobotModelLoaderPtr& rm_loader,
92 const std::string&
name)
95 , private_executor_(std::make_shared<
rclcpp::executors::SingleThreadedExecutor>())
96 , tf_buffer_(std::make_shared<
tf2_ros::Buffer>(node->get_clock()))
97 , dt_state_update_(0.0)
98 , shape_transform_cache_lookup_wait_time_(0, 0)
99 , rm_loader_(rm_loader)
101 std::vector<std::string> new_args = rclcpp::NodeOptions().arguments();
102 new_args.push_back(
"--ros-args");
103 new_args.push_back(
"-r");
105 new_args.push_back(std::string(
"__node:=") +
node_->get_name() +
"_private_" +
106 std::to_string(
reinterpret_cast<std::size_t
>(
this)));
107 new_args.push_back(
"--");
108 pnode_ = std::make_shared<rclcpp::Node>(
"_",
node_->get_namespace(), rclcpp::NodeOptions().arguments(new_args));
118 use_sim_time_ = node->get_parameter(
"use_sim_time").as_bool();
142 robot_model_.reset();
151 if (rm_loader_->getModel())
153 robot_model_ = rm_loader_->getModel();
159 scene_ = std::make_shared<planning_scene::PlanningScene>(rm_loader_->getModel());
167 scene_->getCollisionEnvNonConst()->setLinkPadding(it.first, it.second);
171 scene_->getCollisionEnvNonConst()->setLinkScale(it.first, it.second);
176 RCLCPP_ERROR(LOGGER,
"Configuration of planning scene failed");
189 scene_->setCollisionObjectUpdateCallback(
197 RCLCPP_ERROR(LOGGER,
"Robot model not loaded");
204 last_robot_state_update_wall_time_ = std::chrono::system_clock::now();
205 dt_state_update_ = std::chrono::duration<double>(0.03);
207 double temp_wait_time = 0.05;
210 node_->get_parameter_or(
robot_description_ +
"_planning.shape_transform_cache_lookup_wait_time", temp_wait_time,
213 shape_transform_cache_lookup_wait_time_ = rclcpp::Duration::from_seconds(temp_wait_time);
215 state_update_pending_ =
false;
217 using std::chrono::nanoseconds;
218 state_update_timer_ =
pnode_->create_wall_timer(dt_state_update_, [
this]() {
return stateUpdateTimerCallback(); });
227 rcl_interfaces::msg::ParameterDescriptor desc;
229 return pnode_->declare_parameter(param_name, default_val, desc);
235 bool publish_planning_scene =
236 declare_parameter(
"publish_planning_scene",
false,
"Set to True to publish Planning Scenes");
237 bool publish_geometry_updates =
declare_parameter(
"publish_geometry_updates",
false,
238 "Set to True to publish geometry updates of the planning scene");
239 bool publish_state_updates =
240 declare_parameter(
"publish_state_updates",
false,
"Set to True to publish state updates of the planning scene");
242 "publish_transforms_updates",
false,
"Set to True to publish transform updates of the planning scene");
244 "publish_planning_scene_hz", 4.0,
"Set the maximum frequency at which planning scene updates are published");
245 updatePublishSettings(publish_geometry_updates, publish_state_updates, publish_transform_updates,
246 publish_planning_scene, publish_planning_scene_hz);
248 catch (
const rclcpp::exceptions::InvalidParameterTypeException& e)
250 RCLCPP_ERROR_STREAM(LOGGER,
"Invalid parameter type in PlanningSceneMonitor: " << e.what());
251 RCLCPP_ERROR(LOGGER,
"Dynamic publishing parameters won't be available");
255 auto psm_parameter_set_callback = [
this](
const std::vector<rclcpp::Parameter>& parameters) ->
auto
257 auto result = rcl_interfaces::msg::SetParametersResult();
258 result.successful =
true;
260 bool publish_planning_scene =
false, publish_geometry_updates =
false, publish_state_updates =
false,
261 publish_transform_updates =
false;
262 double publish_planning_scene_hz = 4.0;
263 bool declared_params_valid =
pnode_->get_parameter(
"publish_planning_scene", publish_planning_scene) &&
264 pnode_->get_parameter(
"publish_geometry_updates", publish_geometry_updates) &&
265 pnode_->get_parameter(
"publish_state_updates", publish_state_updates) &&
266 pnode_->get_parameter(
"publish_transforms_updates", publish_transform_updates) &&
267 pnode_->get_parameter(
"publish_planning_scene_hz", publish_planning_scene_hz);
269 if (!declared_params_valid)
271 RCLCPP_ERROR(LOGGER,
"Initially declared parameters are invalid - failed to process update callback");
272 result.successful =
false;
276 for (
const auto& parameter : parameters)
278 const auto&
name = parameter.get_name();
279 const auto&
type = parameter.get_type();
284 RCLCPP_ERROR(LOGGER,
"Invalid parameter in PlanningSceneMonitor parameter callback");
285 result.successful =
false;
290 if (
name ==
"planning_scene_monitor.publish_planning_scene")
291 publish_planning_scene = parameter.as_bool();
292 else if (
name ==
"planning_scene_monitor.publish_geometry_updates")
293 publish_geometry_updates = parameter.as_bool();
294 else if (
name ==
"planning_scene_monitor.publish_state_updates")
295 publish_state_updates = parameter.as_bool();
296 else if (
name ==
"planning_scene_monitor.publish_transforms_updates")
297 publish_transform_updates = parameter.as_bool();
298 else if (
name ==
"planning_scene_monitor.publish_planning_scene_hz")
299 publish_planning_scene_hz = parameter.as_double();
302 if (result.successful)
303 updatePublishSettings(publish_geometry_updates, publish_state_updates, publish_transform_updates,
304 publish_planning_scene, publish_planning_scene_hz);
308 callback_handler_ =
pnode_->add_on_set_parameters_callback(psm_parameter_set_callback);
329 scene_->setCollisionObjectUpdateCallback(
330 [
this](
const collision_detection::World::ObjectConstPtr&
object,
338 RCLCPP_WARN(LOGGER,
"Diff monitoring was stopped while publishing planning scene diffs. "
339 "Stopping planning scene diff publisher");
349 if (!
scene_->getName().empty())
351 if (
scene_->getName()[
scene_->getName().length() - 1] ==
'+')
364 std::unique_ptr<std::thread> copy;
370 RCLCPP_INFO(LOGGER,
"Stopped publishing maintained planning scene.");
375 const std::string& planning_scene_topic)
381 RCLCPP_INFO(LOGGER,
"Publishing maintained planning scene on '%s'", planning_scene_topic.c_str());
387 void PlanningSceneMonitor::scenePublishingThread()
389 RCLCPP_DEBUG(LOGGER,
"Started scene publishing thread ...");
393 moveit_msgs::msg::PlanningScene msg;
398 scene_->getPlanningSceneMsg(msg);
401 RCLCPP_DEBUG(LOGGER,
"Published the full planning scene: '%s'", msg.name.c_str());
406 moveit_msgs::msg::PlanningScene msg;
407 bool publish_msg =
false;
408 bool is_full =
false;
425 scene_->getPlanningSceneDiffMsg(msg);
428 msg.robot_state.attached_collision_objects.clear();
429 msg.robot_state.is_diff =
true;
444 scene_->setCollisionObjectUpdateCallback(
445 [
this](
const collision_detection::World::ObjectConstPtr&
object,
457 scene_->getPlanningSceneMsg(msg);
470 RCLCPP_DEBUG(LOGGER,
"Published full planning scene: '%s'", msg.name.c_str());
498 bool sceneIsParentOf(
const planning_scene::PlanningSceneConstPtr&
scene,
504 return sceneIsParentOf(
scene->getParent(), possible_parent);
525 update_callback(update_type);
534 RCLCPP_FATAL_STREAM(LOGGER,
"requestPlanningSceneState() to self-provided service '" << service_name <<
"'");
535 throw std::runtime_error(
"requestPlanningSceneState() to self-provided service: " + service_name);
538 auto client =
pnode_->create_client<moveit_msgs::srv::GetPlanningScene>(service_name);
539 auto srv = std::make_shared<moveit_msgs::srv::GetPlanningScene::Request>();
540 srv->components.components = srv->components.SCENE_SETTINGS | srv->components.ROBOT_STATE |
541 srv->components.ROBOT_STATE_ATTACHED_OBJECTS | srv->components.WORLD_OBJECT_NAMES |
542 srv->components.WORLD_OBJECT_GEOMETRY | srv->components.OCTOMAP |
543 srv->components.TRANSFORMS | srv->components.ALLOWED_COLLISION_MATRIX |
544 srv->components.LINK_PADDING_AND_SCALING | srv->components.OBJECT_COLORS;
547 RCLCPP_DEBUG(LOGGER,
"Waiting for GetPlanningScene service `%s` to exist.", service_name.c_str());
548 if (client->wait_for_service(std::chrono::seconds(5)))
550 RCLCPP_DEBUG(LOGGER,
"Sending service request to `%s`.", service_name.c_str());
551 auto service_result = client->async_send_request(srv);
552 const auto service_result_status = service_result.wait_for(std::chrono::seconds(5));
553 if (service_result_status == std::future_status::ready)
555 RCLCPP_DEBUG(LOGGER,
"Service request succeeded, applying new planning scene");
559 if (service_result_status == std::future_status::timeout)
561 RCLCPP_INFO(LOGGER,
"GetPlanningScene service call to %s timed out. at %s:%d", service_name.c_str(), __FILE__,
569 "Failed to call service %s, have you launched move_group or called psm.providePlanningSceneService()?",
570 service_name.c_str());
579 service_name, [
this](
const moveit_msgs::srv::GetPlanningScene::Request::SharedPtr& req,
580 const moveit_msgs::srv::GetPlanningScene::Response::SharedPtr& res) {
581 return getPlanningSceneServiceCallback(req, res);
585 void PlanningSceneMonitor::getPlanningSceneServiceCallback(
586 const moveit_msgs::srv::GetPlanningScene::Request::SharedPtr& req,
587 const moveit_msgs::srv::GetPlanningScene::Response::SharedPtr& res)
589 if (req->components.components & moveit_msgs::msg::PlanningSceneComponents::TRANSFORMS)
592 moveit_msgs::msg::PlanningSceneComponents all_components;
593 all_components.components = UINT_MAX;
596 scene_->getPlanningSceneMsg(res->scene, req->components.components ? req->components : all_components);
599 void PlanningSceneMonitor::updatePublishSettings(
bool publish_geom_updates,
bool publish_state_updates,
600 bool publish_transform_updates,
bool publish_planning_scene,
601 double publish_planning_scene_hz)
604 if (publish_geom_updates)
607 if (publish_state_updates)
610 if (publish_transform_updates)
613 if (publish_planning_scene)
622 void PlanningSceneMonitor::newPlanningSceneCallback(
const moveit_msgs::msg::PlanningScene::ConstSharedPtr&
scene)
629 bool removed =
false;
632 removed =
scene_->getWorldNonConst()->removeObject(
scene_->OCTOMAP_NS);
642 RCLCPP_WARN(LOGGER,
"Unable to clear octomap since no octomap monitor has been initialized");
658 std::string old_scene_name;
666 RCLCPP_DEBUG(LOGGER,
"scene update %f robot stamp: %f", fmod(
last_update_time_.seconds(), 10.),
668 old_scene_name =
scene_->getName();
686 if (!
scene.is_diff &&
scene.world.octomap.octomap.data.empty())
693 robot_model_ =
scene_->getRobotModel();
705 bool no_other_scene_upd = (
scene.name.empty() ||
scene.name == old_scene_name) &&
706 scene.allowed_collision_matrix.entry_names.empty() &&
scene.link_padding.empty() &&
707 scene.link_scale.empty();
708 if (no_other_scene_upd)
714 if (!
scene.fixed_frame_transforms.empty())
720 if (!
scene.robot_state.attached_collision_objects.empty() || !
scene.robot_state.is_diff)
730 const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr& world)
738 scene_->getWorldNonConst()->clearObjects();
739 scene_->processPlanningSceneWorldMsg(*world);
742 if (world->octomap.octomap.data.empty())
763 if (!
scene_->processCollisionObjectMsg(*obj))
777 scene_->processAttachedCollisionObjectMsg(*obj);
791 const std::vector<const moveit::core::LinkModel*>& links =
getRobotModel()->getLinkModelsWithCollisionGeometry();
792 auto start = std::chrono::system_clock::now();
796 std::vector<shapes::ShapeConstPtr>
shapes = link->getShapes();
797 for (std::size_t j = 0; j <
shapes.size(); ++j)
802 shapes::Mesh* m =
static_cast<shapes::Mesh*
>(
shapes[j]->clone());
803 m->mergeVertices(1e-4);
812 if (!warned && ((std::chrono::system_clock::now() - start) > std::chrono::seconds(30)))
814 RCLCPP_WARN(LOGGER,
"It is likely there are too many vertices in collision geometry");
828 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
830 for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : link_shape_handle.second)
844 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& attached_body_shape_handle :
846 for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& it : attached_body_shape_handle.second)
857 std::vector<const moveit::core::AttachedBody*> ab;
858 scene_->getCurrentState().getAttachedBodies(ab);
871 for (std::pair<
const std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
873 for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
874 collision_body_shape_handle.second)
884 for (
const std::pair<const std::string, collision_detection::World::ObjectPtr>& it : *
scene_->getWorld())
895 for (std::size_t i = 0; i < attached_body->
getShapes().size(); ++i)
897 if (attached_body->
getShapes()[i]->type == shapes::PLANE || attached_body->
getShapes()[i]->type == shapes::OCTREE)
907 RCLCPP_DEBUG(LOGGER,
"Excluding attached body '%s' from monitored octomap", attached_body->
getName().c_str());
920 for (std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>& shape_handle : it->second)
922 RCLCPP_DEBUG(LOGGER,
"Including attached body '%s' in monitored octomap", attached_body->
getName().c_str());
935 for (std::size_t i = 0; i < obj->shapes_.size(); ++i)
937 if (obj->shapes_[i]->type == shapes::PLANE || obj->shapes_[i]->type == shapes::OCTREE)
947 RCLCPP_DEBUG(LOGGER,
"Excluding collision object '%s' from monitored octomap", obj->id_.c_str());
960 for (std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& shape_handle : it->second)
962 RCLCPP_DEBUG(LOGGER,
"Including collision object '%s' in monitored octomap", obj->id_.c_str());
1000 if (t.nanoseconds() == 0)
1002 RCLCPP_DEBUG(LOGGER,
"sync robot state to: %.3fs", fmod(t.seconds(), 10.));
1014 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1015 if (state_update_pending_)
1017 state_update_pending_ =
false;
1018 last_robot_state_update_wall_time_ = std::chrono::system_clock::now();
1025 RCLCPP_WARN(LOGGER,
"Failed to fetch current robot state.");
1032 auto start =
node_->get_clock()->now();
1033 auto timeout = rclcpp::Duration::from_seconds(wait_time);
1037 timeout > rclcpp::Duration(0, 0))
1041 timeout = timeout - (
node_->get_clock()->now() - start);
1046 RCLCPP_WARN(LOGGER,
"Maybe failed to update robot state, time diff: %.3fs", (t -
last_robot_motion_time_).seconds());
1085 RCLCPP_INFO(LOGGER,
"Starting planning scene monitor");
1087 if (!scene_topic.empty())
1090 scene_topic, rclcpp::SystemDefaultsQoS(), [
this](
const moveit_msgs::msg::PlanningScene::ConstSharedPtr&
scene) {
1091 return newPlanningSceneCallback(
scene);
1101 RCLCPP_INFO(LOGGER,
"Stopping planning scene monitor");
1114 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>& link_shape_handle :
1117 if (
tf_buffer_->canTransform(target_frame, link_shape_handle.first->getName(), target_time,
1118 shape_transform_cache_lookup_wait_time_))
1120 Eigen::Isometry3d ttr = tf2::transformToEigen(
1121 tf_buffer_->lookupTransform(target_frame, link_shape_handle.first->getName(), target_time));
1122 for (std::size_t j = 0; j < link_shape_handle.second.size(); ++j)
1123 cache[link_shape_handle.second[j].first] =
1124 ttr * link_shape_handle.first->getCollisionOriginTransforms()[link_shape_handle.second[j].second];
1128 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t>>>&
1131 if (
tf_buffer_->canTransform(target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time,
1132 shape_transform_cache_lookup_wait_time_))
1134 Eigen::Isometry3d transform = tf2::transformToEigen(
tf_buffer_->lookupTransform(
1135 target_frame, attached_body_shape_handle.first->getAttachedLinkName(), target_time));
1136 for (std::size_t k = 0; k < attached_body_shape_handle.second.size(); ++k)
1137 cache[attached_body_shape_handle.second[k].first] =
1139 attached_body_shape_handle.first->getShapePosesInLinkFrame()[attached_body_shape_handle.second[k].second];
1143 if (
tf_buffer_->canTransform(target_frame,
scene_->getPlanningFrame(), target_time,
1144 shape_transform_cache_lookup_wait_time_))
1146 Eigen::Isometry3d transform =
1147 tf2::transformToEigen(
tf_buffer_->lookupTransform(target_frame,
scene_->getPlanningFrame(), target_time));
1148 for (
const std::pair<
const std::string,
1149 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>>>&
1151 for (
const std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Isometry3d*>& it :
1152 collision_body_shape_handle.second)
1153 cache[it.first] = transform * (*it.second);
1157 catch (tf2::TransformException& ex)
1159 rclcpp::Clock steady_clock = rclcpp::Clock();
1160 RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000,
"Transform error: %s", ex.what());
1167 const std::string& planning_scene_world_topic,
1168 const bool load_octomap_monitor)
1171 RCLCPP_INFO(LOGGER,
"Starting world geometry update monitor for collision objects, attached objects, octomap "
1175 if (!collision_objects_topic.empty())
1178 collision_objects_topic, rclcpp::SystemDefaultsQoS(),
1179 [
this](
const moveit_msgs::msg::CollisionObject::ConstSharedPtr& obj) {
return collisionObjectCallback(obj); });
1180 RCLCPP_INFO(LOGGER,
"Listening to '%s'", collision_objects_topic.c_str());
1183 if (!planning_scene_world_topic.empty())
1186 planning_scene_world_topic, rclcpp::SystemDefaultsQoS(),
1187 [
this](
const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr& world) {
1190 RCLCPP_INFO(LOGGER,
"Listening to '%s' for planning scene world geometry", planning_scene_world_topic.c_str());
1194 if (load_octomap_monitor)
1199 std::make_unique<occupancy_map_monitor::OccupancyMapMonitor>(
node_,
tf_buffer_,
scene_->getPlanningFrame());
1204 octomap_monitor_->setTransformCacheCallback([
this](
const std::string& frame,
const rclcpp::Time& stamp,
1218 RCLCPP_INFO(LOGGER,
"Stopping world geometry monitor");
1223 RCLCPP_INFO(LOGGER,
"Stopping world geometry monitor");
1231 const std::string& attached_objects_topic)
1242 [
this](
const sensor_msgs::msg::JointState::ConstSharedPtr& joint_state) {
return onStateUpdate(joint_state); });
1246 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1247 if (dt_state_update_.count() > 0)
1250 state_update_timer_ =
1251 pnode_->create_wall_timer(dt_state_update_, [
this]() {
return stateUpdateTimerCallback(); });
1254 if (!attached_objects_topic.empty())
1258 attached_objects_topic, rclcpp::SystemDefaultsQoS(),
1259 [
this](
const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr& obj) {
1262 RCLCPP_INFO(LOGGER,
"Listening to '%s' for attached collision objects",
1267 RCLCPP_ERROR(LOGGER,
"Cannot monitor robot state because planning scene is not configured");
1278 if (state_update_timer_)
1279 state_update_timer_->cancel();
1281 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1282 state_update_pending_ =
false;
1286 void PlanningSceneMonitor::onStateUpdate(
const sensor_msgs::msg::JointState::ConstSharedPtr& )
1288 const std::chrono::system_clock::time_point& n = std::chrono::system_clock::now();
1289 std::chrono::duration<double> dt = n - last_robot_state_update_wall_time_;
1291 bool update =
false;
1293 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1295 if (dt.count() < dt_state_update_.count())
1297 state_update_pending_ =
true;
1301 state_update_pending_ =
false;
1302 last_robot_state_update_wall_time_ = n;
1311 void PlanningSceneMonitor::stateUpdateTimerCallback()
1313 if (state_update_pending_)
1315 bool update =
false;
1317 std::chrono::system_clock::time_point n = std::chrono::system_clock::now();
1318 std::chrono::duration<double> dt = n - last_robot_state_update_wall_time_;
1322 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1323 if (state_update_pending_ && dt.count() >= dt_state_update_.count())
1325 state_update_pending_ =
false;
1326 last_robot_state_update_wall_time_ = std::chrono::system_clock::now();
1327 auto sec = std::chrono::duration<double>(last_robot_state_update_wall_time_.time_since_epoch()).count();
1329 RCLCPP_DEBUG(LOGGER,
"performPendingStateUpdate: %f", fmod(sec, 10));
1337 RCLCPP_DEBUG(LOGGER,
"performPendingStateUpdate done");
1368 bool update =
false;
1369 if (hz > std::numeric_limits<double>::epsilon())
1371 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1372 dt_state_update_ = std::chrono::duration<double>(1.0 / hz);
1375 state_update_timer_ =
pnode_->create_wall_timer(dt_state_update_, [
this]() {
return stateUpdateTimerCallback(); });
1382 if (state_update_timer_)
1383 state_update_timer_->cancel();
1384 std::unique_lock<std::mutex> lock(state_pending_mutex_);
1385 dt_state_update_ = std::chrono::duration<double>(0.0);
1386 if (state_update_pending_)
1389 RCLCPP_INFO(LOGGER,
"Updating internal planning scene state at most every %lf seconds", dt_state_update_.count());
1397 rclcpp::Time time =
node_->now();
1398 rclcpp::Clock steady_clock = rclcpp::Clock(RCL_STEADY_TIME);
1401 std::vector<std::string> missing;
1405 std::string missing_str = boost::algorithm::join(missing,
", ");
1406 RCLCPP_WARN_THROTTLE(LOGGER, steady_clock, 1000,
"The complete state of the robot is not yet known. Missing %s",
1407 missing_str.c_str());
1415 scene_->getCurrentStateNonConst().update();
1420 RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000,
1421 "State monitor is not active. Unable to set the planning scene state");
1440 RCLCPP_DEBUG(LOGGER,
"Maximum frequency for publishing a planning scene is now %lf Hz",
1444 void PlanningSceneMonitor::getUpdatedFrameTransforms(std::vector<geometry_msgs::msg::TransformStamped>& transforms)
1446 const std::string& target =
getRobotModel()->getModelFrame();
1448 std::vector<std::string> all_frame_names;
1449 tf_buffer_->_getFrameStrings(all_frame_names);
1450 for (
const std::string& all_frame_name : all_frame_names)
1452 if (all_frame_name == target ||
getRobotModel()->hasLinkModel(all_frame_name))
1455 geometry_msgs::msg::TransformStamped
f;
1458 f =
tf_buffer_->lookupTransform(target, all_frame_name, tf2::TimePointZero);
1460 catch (tf2::TransformException& ex)
1462 RCLCPP_WARN(LOGGER,
"Unable to transform object from frame '%s' to planning frame'%s' (%s)",
1463 all_frame_name.c_str(), target.c_str(), ex.what());
1466 f.header.frame_id = all_frame_name;
1467 f.child_frame_id = target;
1468 transforms.push_back(
f);
1476 std::vector<geometry_msgs::msg::TransformStamped> transforms;
1477 getUpdatedFrameTransforms(transforms);
1480 scene_->getTransformsNonConst().setTransforms(transforms);
1504 RCLCPP_DEBUG(LOGGER,
"No additional default collision operations specified");
1507 RCLCPP_DEBUG(LOGGER,
"Reading additional default collision operations");
1551 static const std::string ROBOT_DESCRIPTION =
void setupScene(const rclcpp::Node::SharedPtr &node, const planning_scene::PlanningScenePtr &scene)
Fetch plugin name from parameter server and activate the plugin for the given scene.
std::shared_lock< std::shared_mutex > ReadLock
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
This may be thrown during construction of objects if errors occur.
Object defining bodies that can be attached to robot links.
const std::string & getName() const
Get the name of the attached body.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
A link from the robot. Contains the constant transform applied to the link and its geometry.
This class maintains the representation of the environment as seen by a planning instance....
static const std::string OCTOMAP_NS
PlanningSceneMonitor Subscribes to the topic planning_scene.
void lockSceneRead()
Lock the scene for reading (multiple threads can lock for reading at the same time)
void lockSceneWrite()
Lock the scene for writing (only one thread can lock for writing and no other thread can lock for rea...
void unlockSceneRead()
Unlock the scene from reading (multiple threads can lock for reading at the same time)
void excludeAttachedBodiesFromOctree()
planning_scene::PlanningScenePtr scene_
double default_attached_padd_
default attached padding
void currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr &object, collision_detection::World::Action action)
Callback for a change in the world maintained by the planning scene.
double default_robot_scale_
default robot scaling
std::unique_ptr< occupancy_map_monitor::OccupancyMapMonitor > octomap_monitor_
const moveit::core::RobotModelConstPtr & getRobotModel() const
AttachedBodyShapeHandles attached_body_shape_handles_
void attachObjectCallback(const moveit_msgs::msg::AttachedCollisionObject::ConstSharedPtr &obj)
Callback for a new attached object msg.
std::map< std::string, double > default_robot_link_padd_
default robot link padding
LinkShapeHandles link_shape_handles_
void collisionObjectCallback(const moveit_msgs::msg::CollisionObject::ConstSharedPtr &obj)
Callback for a new collision object msg.
SceneUpdateType publish_update_types_
void configureDefaultPadding()
Configure the default padding.
void publishDebugInformation(bool flag)
PlanningSceneMonitor(const PlanningSceneMonitor &)=delete
PlanningSceneMonitor cannot be copy-constructed.
rclcpp::Subscription< moveit_msgs::msg::AttachedCollisionObject >::SharedPtr attached_collision_object_subscriber_
void stopPublishingPlanningScene()
Stop publishing the maintained planning scene.
void excludeAttachedBodyFromOctree(const moveit::core::AttachedBody *attached_body)
double default_object_padd_
default object padding
void addUpdateCallback(const std::function< void(SceneUpdateType)> &fn)
Add a function to be called when an update to the scene is received.
std::shared_ptr< rclcpp::Node > pnode_
bool newPlanningSceneMessage(const moveit_msgs::msg::PlanningScene &scene)
void setPlanningScenePublishingFrequency(double hz)
Set the maximum frequency at which planning scenes are being published.
void includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr &obj)
rclcpp::Service< moveit_msgs::srv::GetPlanningScene >::SharedPtr get_scene_service_
void initialize(const planning_scene::PlanningScenePtr &scene)
Initialize the planning scene monitor.
void getMonitoredTopics(std::vector< std::string > &topics) const
Get the topic names that the monitor is listening to.
void triggerSceneUpdateEvent(SceneUpdateType update_type)
This function is called every time there is a change to the planning scene.
void newPlanningSceneWorldCallback(const moveit_msgs::msg::PlanningSceneWorld::ConstSharedPtr &world)
Callback for a new planning scene world.
planning_scene::PlanningSceneConstPtr scene_const_
rclcpp::Subscription< moveit_msgs::msg::CollisionObject >::SharedPtr collision_object_subscriber_
void includeAttachedBodyInOctree(const moveit::core::AttachedBody *attached_body)
void octomapUpdateCallback()
Callback for octomap updates.
rclcpp::Subscription< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_subscriber_
void clearUpdateCallbacks()
Clear the functions to be called when an update to the scene is received.
void providePlanningSceneService(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Create an optional service for getting the complete planning scene This is useful for satisfying the ...
std::shared_mutex scene_update_mutex_
if diffs are monitored, this is the pointer to the parent scene
void setStateUpdateFrequency(double hz)
Update the scene using the monitored state at a specified frequency, in Hz. This function has an effe...
double publish_planning_scene_frequency_
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
void stopWorldGeometryMonitor()
Stop the world geometry monitor.
void startStateMonitor(const std::string &joint_states_topic=DEFAULT_JOINT_STATES_TOPIC, const std::string &attached_objects_topic=DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC)
Start the current state monitor.
void stopStateMonitor()
Stop the state monitor.
@ UPDATE_SCENE
The entire scene was updated.
@ UPDATE_STATE
The state in the monitored scene was updated.
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
@ UPDATE_TRANSFORMS
The maintained set of fixed transforms in the monitored scene was updated.
std::atomic< SceneUpdateType > new_scene_update_
std::shared_ptr< rclcpp::executors::SingleThreadedExecutor > private_executor_
void includeAttachedBodiesInOctree()
bool getShapeTransformCache(const std::string &target_frame, const rclcpp::Time &target_time, occupancy_map_monitor::ShapeTransformCache &cache) const
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
void startPublishingPlanningScene(SceneUpdateType event, const std::string &planning_scene_topic=MONITORED_PLANNING_SCENE_TOPIC)
Start publishing the maintained planning scene. The first message set out is a complete planning scen...
std::string robot_description_
bool waitForCurrentRobotState(const rclcpp::Time &t, double wait_time=1.)
Wait for robot state to become more recent than time t.
std::recursive_mutex shape_handles_lock_
std::map< std::string, double > default_robot_link_scale_
default robot link scale
void updateSceneWithCurrentState()
Update the scene using the monitored state. This function is automatically called when an update to t...
rclcpp::Time last_robot_motion_time_
Last time the state was updated.
std::thread private_executor_thread_
void excludeWorldObjectsFromOctree()
double default_robot_padd_
default robot padding
std::string monitor_name_
The name of this scene monitor.
bool updatesScene(const planning_scene::PlanningSceneConstPtr &scene) const
Return true if the scene scene can be updated directly or indirectly by this monitor....
CurrentStateMonitorPtr current_state_monitor_
std::recursive_mutex update_lock_
lock access to update_callbacks_
void includeWorldObjectsInOctree()
CollisionBodyShapeHandles collision_body_shape_handles_
void stopSceneMonitor()
Stop the scene monitor.
void includeRobotLinksInOctree()
rclcpp::Time last_update_time_
mutex for stored scene
void excludeRobotLinksFromOctree()
bool requestPlanningSceneState(const std::string &service_name=DEFAULT_PLANNING_SCENE_SERVICE)
Request a full planning scene state using a service call Be careful not to use this in conjunction wi...
void monitorDiffs(bool flag)
By default, the maintained planning scene does not reason about diffs. When the flag passed in is tru...
void currentStateAttachedBodyUpdateCallback(moveit::core::AttachedBody *attached_body, bool just_attached)
Callback for a change for an attached object of the current state of the planning scene.
std::unique_ptr< std::thread > publish_planning_scene_
std::shared_ptr< rclcpp::Node > node_
Last time the robot has moved.
void configureCollisionMatrix(const planning_scene::PlanningScenePtr &scene)
Configure the collision matrix for a particular scene.
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
Start the OccupancyMapMonitor and listening for:
rclcpp::Publisher< moveit_msgs::msg::PlanningScene >::SharedPtr planning_scene_publisher_
void excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr &obj)
std::vector< std::function< void(SceneUpdateType)> > update_callbacks_
void updateFrameTransforms()
Update the transforms for the frames that are not part of the kinematic model using tf....
planning_scene::PlanningScenePtr parent_scene_
std::condition_variable_any new_scene_update_condition_
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
void unlockSceneWrite()
Lock the scene from writing (only one thread can lock for writing and no other thread can lock for re...
rclcpp::Subscription< moveit_msgs::msg::PlanningSceneWorld >::SharedPtr planning_scene_world_subscriber_
rclcpp::Parameter declare_parameter(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_name)
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER