Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_PLANNING_SCENE_MONITOR_PLANNING_SCENE_MONITOR_
00038 #define MOVEIT_PLANNING_SCENE_MONITOR_PLANNING_SCENE_MONITOR_
00039
00040 #include <ros/ros.h>
00041 #include <tf/tf.h>
00042 #include <tf/message_filter.h>
00043 #include <message_filters/subscriber.h>
00044 #include <moveit/macros/class_forward.h>
00045 #include <moveit/planning_scene/planning_scene.h>
00046 #include <moveit/robot_model_loader/robot_model_loader.h>
00047 #include <moveit/occupancy_map_monitor/occupancy_map_monitor.h>
00048 #include <moveit/planning_scene_monitor/current_state_monitor.h>
00049 #include <moveit/collision_plugin_loader/collision_plugin_loader.h>
00050 #include <boost/noncopyable.hpp>
00051 #include <boost/thread/shared_mutex.hpp>
00052 #include <boost/thread/recursive_mutex.hpp>
00053
00054 namespace planning_scene_monitor
00055 {
00056 MOVEIT_CLASS_FORWARD(PlanningSceneMonitor);
00057
00061 class PlanningSceneMonitor : private boost::noncopyable
00062 {
00063 public:
00064 enum SceneUpdateType
00065 {
00067 UPDATE_NONE = 0,
00068
00070 UPDATE_STATE = 1,
00071
00073 UPDATE_TRANSFORMS = 2,
00074
00077 UPDATE_GEOMETRY = 4,
00078
00080 UPDATE_SCENE = 8 + UPDATE_STATE + UPDATE_TRANSFORMS + UPDATE_GEOMETRY
00081 };
00082
00084 static const std::string DEFAULT_JOINT_STATES_TOPIC;
00085
00087 static const std::string DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC;
00088
00090 static const std::string DEFAULT_COLLISION_OBJECT_TOPIC;
00091
00094 static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC;
00095
00097 static const std::string DEFAULT_PLANNING_SCENE_TOPIC;
00098
00100 static const std::string DEFAULT_PLANNING_SCENE_SERVICE;
00101
00104 static const std::string MONITORED_PLANNING_SCENE_TOPIC;
00105
00111 PlanningSceneMonitor(const std::string& robot_description,
00112 const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>(),
00113 const std::string& name = "");
00114
00120 PlanningSceneMonitor(const robot_model_loader::RobotModelLoaderPtr& rml,
00121 const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>(),
00122 const std::string& name = "");
00123
00130 PlanningSceneMonitor(const planning_scene::PlanningScenePtr& scene, const std::string& robot_description,
00131 const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>(),
00132 const std::string& name = "");
00133
00140 PlanningSceneMonitor(const planning_scene::PlanningScenePtr& scene,
00141 const robot_model_loader::RobotModelLoaderPtr& rml,
00142 const boost::shared_ptr<tf::Transformer>& tf = boost::shared_ptr<tf::Transformer>(),
00143 const std::string& name = "");
00144
00145 ~PlanningSceneMonitor();
00146
00148 const std::string& getName() const
00149 {
00150 return monitor_name_;
00151 }
00152
00154 const robot_model_loader::RobotModelLoaderPtr& getRobotModelLoader() const
00155 {
00156 return rm_loader_;
00157 }
00158
00159 const robot_model::RobotModelConstPtr& getRobotModel() const
00160 {
00161 return robot_model_;
00162 }
00163
00178 const planning_scene::PlanningScenePtr& getPlanningScene()
00179 {
00180 return scene_;
00181 }
00182
00186 const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
00187 {
00188 return scene_const_;
00189 }
00190
00195 bool updatesScene(const planning_scene::PlanningSceneConstPtr& scene) const;
00196
00201 bool updatesScene(const planning_scene::PlanningScenePtr& scene) const;
00202
00205 const std::string& getRobotDescription() const
00206 {
00207 return robot_description_;
00208 }
00209
00211 double getDefaultRobotPadding() const
00212 {
00213 return default_robot_padd_;
00214 }
00215
00217 double getDefaultRobotScale() const
00218 {
00219 return default_robot_scale_;
00220 }
00221
00223 double getDefaultObjectPadding() const
00224 {
00225 return default_object_padd_;
00226 }
00227
00229 double getDefaultAttachedObjectPadding() const
00230 {
00231 return default_attached_padd_;
00232 }
00233
00235 const boost::shared_ptr<tf::Transformer>& getTFClient() const
00236 {
00237 return tf_;
00238 }
00239
00245 void monitorDiffs(bool flag);
00246
00250 void startPublishingPlanningScene(SceneUpdateType event,
00251 const std::string& planning_scene_topic = MONITORED_PLANNING_SCENE_TOPIC);
00252
00254 void stopPublishingPlanningScene();
00255
00257 void setPlanningScenePublishingFrequency(double hz);
00258
00260 double getPlanningScenePublishingFrequency() const
00261 {
00262 return publish_planning_scene_frequency_;
00263 }
00264
00267 const CurrentStateMonitorPtr& getStateMonitor() const
00268 {
00269 return current_state_monitor_;
00270 }
00271
00272 CurrentStateMonitorPtr& getStateMonitorNonConst()
00273 {
00274 return current_state_monitor_;
00275 }
00276
00282 void updateFrameTransforms();
00283
00287 void startStateMonitor(const std::string& joint_states_topic = DEFAULT_JOINT_STATES_TOPIC,
00288 const std::string& attached_objects_topic = DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC);
00289
00291 void stopStateMonitor();
00292
00296 void updateSceneWithCurrentState();
00297
00303 void setStateUpdateFrequency(double hz);
00304
00306 double getStateUpdateFrequency() const
00307 {
00308 if (!dt_state_update_.isZero())
00309 return 1.0 / dt_state_update_.toSec();
00310 else
00311 return 0.0;
00312 }
00313
00317 void startSceneMonitor(const std::string& scene_topic = DEFAULT_PLANNING_SCENE_TOPIC);
00318
00325 bool requestPlanningSceneState(const std::string& service_name = DEFAULT_PLANNING_SCENE_SERVICE);
00326
00328 void stopSceneMonitor();
00329
00336 void startWorldGeometryMonitor(const std::string& collision_objects_topic = DEFAULT_COLLISION_OBJECT_TOPIC,
00337 const std::string& planning_scene_world_topic = DEFAULT_PLANNING_SCENE_WORLD_TOPIC,
00338 const bool load_octomap_monitor = true);
00339
00341 void stopWorldGeometryMonitor();
00342
00344 void addUpdateCallback(const boost::function<void(SceneUpdateType)>& fn);
00345
00347 void clearUpdateCallbacks();
00348
00350 void getMonitoredTopics(std::vector<std::string>& topics) const;
00351
00353 const ros::Time& getLastUpdateTime() const
00354 {
00355 return last_update_time_;
00356 }
00357
00358 void publishDebugInformation(bool flag);
00359
00361 void triggerSceneUpdateEvent(SceneUpdateType update_type);
00362
00364 void lockSceneRead();
00365
00367 void unlockSceneRead();
00368
00371 void lockSceneWrite();
00372
00375 void unlockSceneWrite();
00376
00377 void clearOctomap();
00378
00379
00380 bool newPlanningSceneMessage(const moveit_msgs::PlanningScene& scene);
00381
00382 protected:
00386 void initialize(const planning_scene::PlanningScenePtr& scene);
00387
00389 void configureCollisionMatrix(const planning_scene::PlanningScenePtr& scene);
00390
00392 void configureDefaultPadding();
00393
00395 void collisionObjectCallback(const moveit_msgs::CollisionObjectConstPtr& obj);
00396
00398 void collisionObjectFailTFCallback(const moveit_msgs::CollisionObjectConstPtr& obj,
00399 tf::filter_failure_reasons::FilterFailureReason reason);
00400
00402 void newPlanningSceneWorldCallback(const moveit_msgs::PlanningSceneWorldConstPtr& world);
00403
00405 void octomapUpdateCallback();
00406
00408 void attachObjectCallback(const moveit_msgs::AttachedCollisionObjectConstPtr& obj);
00409
00411 void currentStateAttachedBodyUpdateCallback(robot_state::AttachedBody* attached_body, bool just_attached);
00412
00414 void currentWorldObjectUpdateCallback(const collision_detection::World::ObjectConstPtr& object,
00415 collision_detection::World::Action action);
00416
00417 void includeRobotLinksInOctree();
00418 void excludeRobotLinksFromOctree();
00419
00420 void excludeWorldObjectsFromOctree();
00421 void includeWorldObjectsInOctree();
00422 void excludeWorldObjectFromOctree(const collision_detection::World::ObjectConstPtr& obj);
00423 void includeWorldObjectInOctree(const collision_detection::World::ObjectConstPtr& obj);
00424
00425 void excludeAttachedBodiesFromOctree();
00426 void includeAttachedBodiesInOctree();
00427 void excludeAttachedBodyFromOctree(const robot_state::AttachedBody* attached_body);
00428 void includeAttachedBodyInOctree(const robot_state::AttachedBody* attached_body);
00429
00430 bool getShapeTransformCache(const std::string& target_frame, const ros::Time& target_time,
00431 occupancy_map_monitor::ShapeTransformCache& cache) const;
00432
00434 std::string monitor_name_;
00435
00436 planning_scene::PlanningScenePtr scene_;
00437 planning_scene::PlanningSceneConstPtr scene_const_;
00438 planning_scene::PlanningScenePtr parent_scene_;
00439 boost::shared_mutex scene_update_mutex_;
00440
00441 ros::NodeHandle nh_;
00442 ros::NodeHandle root_nh_;
00443 boost::shared_ptr<tf::Transformer> tf_;
00444 std::string robot_description_;
00445
00447 double default_robot_padd_;
00449 double default_robot_scale_;
00451 double default_object_padd_;
00453 double default_attached_padd_;
00455 std::map<std::string, double> default_robot_link_padd_;
00457 std::map<std::string, double> default_robot_link_scale_;
00458
00459
00460 ros::Publisher planning_scene_publisher_;
00461 boost::scoped_ptr<boost::thread> publish_planning_scene_;
00462 double publish_planning_scene_frequency_;
00463 SceneUpdateType publish_update_types_;
00464 SceneUpdateType new_scene_update_;
00465 boost::condition_variable_any new_scene_update_condition_;
00466
00467
00468 ros::Subscriber planning_scene_subscriber_;
00469 ros::Subscriber planning_scene_world_subscriber_;
00470
00471 ros::Subscriber attached_collision_object_subscriber_;
00472
00473 boost::scoped_ptr<message_filters::Subscriber<moveit_msgs::CollisionObject> > collision_object_subscriber_;
00474 boost::scoped_ptr<tf::MessageFilter<moveit_msgs::CollisionObject> > collision_object_filter_;
00475
00476
00477 boost::scoped_ptr<occupancy_map_monitor::OccupancyMapMonitor> octomap_monitor_;
00478
00479
00480 CurrentStateMonitorPtr current_state_monitor_;
00481
00482 typedef std::map<const robot_model::LinkModel*,
00483 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >
00484 LinkShapeHandles;
00485 typedef std::map<const robot_state::AttachedBody*,
00486 std::vector<std::pair<occupancy_map_monitor::ShapeHandle, std::size_t> > >
00487 AttachedBodyShapeHandles;
00488 typedef std::map<std::string, std::vector<std::pair<occupancy_map_monitor::ShapeHandle, const Eigen::Affine3d*> > >
00489 CollisionBodyShapeHandles;
00490
00491 LinkShapeHandles link_shape_handles_;
00492 AttachedBodyShapeHandles attached_body_shape_handles_;
00493 CollisionBodyShapeHandles collision_body_shape_handles_;
00494 mutable boost::recursive_mutex shape_handles_lock_;
00495
00497 boost::recursive_mutex update_lock_;
00498 std::vector<boost::function<void(SceneUpdateType)> > update_callbacks_;
00499
00500 ros::Time last_update_time_;
00501
00502 private:
00503 void getUpdatedFrameTransforms(std::vector<geometry_msgs::TransformStamped>& transforms);
00504
00505
00506 void scenePublishingThread();
00507
00508
00509 void onStateUpdate(const sensor_msgs::JointStateConstPtr& joint_state);
00510
00511
00512 void stateUpdateTimerCallback(const ros::WallTimerEvent& event);
00513
00514
00515 void newPlanningSceneCallback(const moveit_msgs::PlanningSceneConstPtr& scene);
00516
00517
00518 boost::mutex state_pending_mutex_;
00519
00521
00522 volatile bool state_update_pending_;
00523
00525
00526 ros::WallDuration dt_state_update_;
00527
00529
00530
00531 ros::Duration shape_transform_cache_lookup_wait_time_;
00532
00534
00535
00536 ros::WallTimer state_update_timer_;
00537
00539
00540 ros::WallTime last_state_update_;
00541
00542 robot_model_loader::RobotModelLoaderPtr rm_loader_;
00543 robot_model::RobotModelConstPtr robot_model_;
00544
00545 collision_detection::CollisionPluginLoader collision_loader_;
00546
00547 class DynamicReconfigureImpl;
00548 DynamicReconfigureImpl* reconfigure_impl_;
00549 };
00550
00572 class LockedPlanningSceneRO
00573 {
00574 public:
00575 LockedPlanningSceneRO(const PlanningSceneMonitorPtr& planning_scene_monitor)
00576 : planning_scene_monitor_(planning_scene_monitor)
00577 {
00578 initialize(true);
00579 }
00580
00581 const PlanningSceneMonitorPtr& getPlanningSceneMonitor()
00582 {
00583 return planning_scene_monitor_;
00584 }
00585
00586 operator bool() const
00587 {
00588 return planning_scene_monitor_ && planning_scene_monitor_->getPlanningScene();
00589 }
00590
00591 operator const planning_scene::PlanningSceneConstPtr&() const
00592 {
00593 return static_cast<const PlanningSceneMonitor*>(planning_scene_monitor_.get())->getPlanningScene();
00594 }
00595
00596 const planning_scene::PlanningSceneConstPtr& operator->() const
00597 {
00598 return static_cast<const PlanningSceneMonitor*>(planning_scene_monitor_.get())->getPlanningScene();
00599 }
00600
00601 protected:
00602 LockedPlanningSceneRO(const PlanningSceneMonitorPtr& planning_scene_monitor, bool read_only)
00603 : planning_scene_monitor_(planning_scene_monitor)
00604 {
00605 initialize(read_only);
00606 }
00607
00608 void initialize(bool read_only)
00609 {
00610 if (planning_scene_monitor_)
00611 lock_.reset(new SingleUnlock(planning_scene_monitor_.get(), read_only));
00612 }
00613
00614 MOVEIT_CLASS_FORWARD(SingleUnlock);
00615
00616
00617
00618 struct SingleUnlock
00619 {
00620 SingleUnlock(PlanningSceneMonitor* planning_scene_monitor, bool read_only)
00621 : planning_scene_monitor_(planning_scene_monitor), read_only_(read_only)
00622 {
00623 if (read_only)
00624 planning_scene_monitor_->lockSceneRead();
00625 else
00626 planning_scene_monitor_->lockSceneWrite();
00627 }
00628 ~SingleUnlock()
00629 {
00630 if (read_only_)
00631 planning_scene_monitor_->unlockSceneRead();
00632 else
00633 planning_scene_monitor_->unlockSceneWrite();
00634 }
00635 PlanningSceneMonitor* planning_scene_monitor_;
00636 bool read_only_;
00637 };
00638
00639 PlanningSceneMonitorPtr planning_scene_monitor_;
00640 SingleUnlockPtr lock_;
00641 };
00642
00664 class LockedPlanningSceneRW : public LockedPlanningSceneRO
00665 {
00666 public:
00667 LockedPlanningSceneRW(const PlanningSceneMonitorPtr& planning_scene_monitor)
00668 : LockedPlanningSceneRO(planning_scene_monitor, false)
00669 {
00670 }
00671
00672 operator const planning_scene::PlanningScenePtr&()
00673 {
00674 return planning_scene_monitor_->getPlanningScene();
00675 }
00676
00677 const planning_scene::PlanningScenePtr& operator->()
00678 {
00679 return planning_scene_monitor_->getPlanningScene();
00680 }
00681 };
00682 }
00683
00684 #endif