00001 /* 00002 * Copyright (C) 2012-2014 Open Source Robotics Foundation 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 * 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 * 00016 */ 00017 /* 00018 * Desc: A plugin which publishes the gazebo world state as a MoveIt! planning scene 00019 * Author: Jonathan Bohren 00020 * Date: 15 May 2014 00021 */ 00022 #ifndef GAZEBO_ROS_MOVEIT_PLANNING_SCENE_H 00023 #define GAZEBO_ROS_MOVEIT_PLANNING_SCENE_H 00024 00025 #include <string> 00026 00027 // Custom Callback Queue 00028 #include <ros/callback_queue.h> 00029 #include <ros/subscribe_options.h> 00030 #include <geometry_msgs/Pose.h> 00031 00032 #include <ros/ros.h> 00033 #include <boost/thread.hpp> 00034 #include <boost/thread/mutex.hpp> 00035 00036 #include <gazebo/physics/physics.hh> 00037 #include <gazebo/transport/TransportTypes.hh> 00038 #include <gazebo/common/Plugin.hh> 00039 #include <gazebo/common/Events.hh> 00040 00041 #include <std_srvs/Empty.h> 00042 #include <moveit_msgs/PlanningScene.h> 00043 00044 namespace gazebo 00045 { 00048 00091 class GazeboRosMoveItPlanningScene : public ModelPlugin 00092 { 00094 public: GazeboRosMoveItPlanningScene(); 00095 00097 public: virtual ~GazeboRosMoveItPlanningScene(); 00098 00099 // Documentation inherited 00100 protected: void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); 00101 00102 // Documentation inherited 00103 protected: virtual void UpdateCB(); 00104 00106 private: bool PublishPlanningSceneCB( 00107 std_srvs::Empty::Request& req, 00108 std_srvs::Empty::Response& resp); 00109 00111 private: void QueueThread(); 00112 00114 private: physics::WorldPtr world_; 00115 00117 private: physics::ModelPtr model_; 00118 00120 private: boost::scoped_ptr<ros::NodeHandle> rosnode_; 00121 private: ros::Publisher planning_scene_pub_; 00122 ros::ServiceServer publish_planning_scene_service_; 00123 00125 private: boost::mutex mutex_; 00126 00128 private: std::string topic_name_; 00130 private: std::string scene_name_; 00131 private: std::string robot_name_; 00132 private: std::string model_name_; 00133 00135 private: std::string robot_namespace_; 00136 00137 // Custom Callback Queue 00138 private: ros::CallbackQueue queue_; 00140 private: boost::thread callback_queue_thread_; 00142 private: moveit_msgs::PlanningScene planning_scene_msg_; 00143 std::map<std::string, moveit_msgs::CollisionObject> collision_object_map_; 00144 00145 // Pointer to the update event connection 00146 private: event::ConnectionPtr update_connection_; 00147 private: event::ConnectionPtr add_connection_; 00148 private: event::ConnectionPtr delete_connection_; 00149 00150 private: 00151 bool publish_full_scene_; 00152 00153 ros::Duration publish_period_; 00154 ros::Time last_publish_time_; 00155 }; 00157 00158 } 00159 #endif