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_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_
00038 #define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_
00039
00040 #include <rviz/display.h>
00041
00042 #ifndef Q_MOC_RUN
00043 #include <moveit/rviz_plugin_render_tools/planning_scene_render.h>
00044 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00045 #include <moveit/background_processing/background_processing.h>
00046 #include <ros/ros.h>
00047 #endif
00048
00049 namespace Ogre
00050 {
00051 class SceneNode;
00052 }
00053
00054 namespace rviz
00055 {
00056 class Robot;
00057 class Property;
00058 class StringProperty;
00059 class BoolProperty;
00060 class FloatProperty;
00061 class RosTopicProperty;
00062 class ColorProperty;
00063 class EnumProperty;
00064 }
00065
00066 namespace moveit_rviz_plugin
00067 {
00068 class PlanningSceneDisplay : public rviz::Display
00069 {
00070 Q_OBJECT
00071
00072 public:
00073 PlanningSceneDisplay(bool listen_to_planning_scene = true, bool show_scene_robot = true);
00074 virtual ~PlanningSceneDisplay();
00075
00076 virtual void load(const rviz::Config& config);
00077 virtual void save(rviz::Config config) const;
00078
00079 virtual void update(float wall_dt, float ros_dt);
00080 virtual void reset();
00081
00082 void setLinkColor(const std::string& link_name, const QColor& color);
00083 void unsetLinkColor(const std::string& link_name);
00084
00085 void queueRenderSceneGeometry();
00086
00089 void addBackgroundJob(const boost::function<void()>& job, const std::string& name);
00090
00095 void spawnBackgroundJob(const boost::function<void()>& job);
00096
00098 void addMainLoopJob(const boost::function<void()>& job);
00099
00100 void waitForAllMainLoopJobs();
00101
00103 void clearJobs();
00104
00105 const std::string getMoveGroupNS() const;
00106 const robot_model::RobotModelConstPtr& getRobotModel() const;
00107 planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const;
00108 planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW();
00109 const planning_scene_monitor::PlanningSceneMonitorPtr& getPlanningSceneMonitor();
00110
00111 private Q_SLOTS:
00112
00113
00114
00115
00116 void changedMoveGroupNS();
00117 void changedRobotDescription();
00118 void changedSceneName();
00119 void changedSceneEnabled();
00120 void changedSceneRobotVisualEnabled();
00121 void changedSceneRobotCollisionEnabled();
00122 void changedRobotSceneAlpha();
00123 void changedSceneAlpha();
00124 void changedSceneColor();
00125 void changedAttachedBodyColor();
00126 void changedPlanningSceneTopic();
00127 void changedSceneDisplayTime();
00128 void changedOctreeRenderMode();
00129 void changedOctreeColorMode();
00130
00131 protected:
00134 void loadRobotModel();
00135
00138 void clearRobotModel();
00139
00142 virtual planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor();
00143
00145 virtual void onRobotModelLoaded();
00146
00150 void calculateOffsetPosition();
00151
00152 void executeMainLoopJobs();
00153 void sceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type);
00154 void renderPlanningScene();
00155 void setLinkColor(rviz::Robot* robot, const std::string& link_name, const QColor& color);
00156 void unsetLinkColor(rviz::Robot* robot, const std::string& link_name);
00157 void setGroupColor(rviz::Robot* robot, const std::string& group_name, const QColor& color);
00158 void unsetGroupColor(rviz::Robot* robot, const std::string& group_name);
00159 void unsetAllColors(rviz::Robot* robot);
00160
00161
00162 virtual void onInitialize();
00163 virtual void onEnable();
00164 virtual void onDisable();
00165 virtual void fixedFrameChanged();
00166
00167
00168 virtual void updateInternal(float wall_dt, float ros_dt);
00169 virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type);
00170
00171 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
00172 bool model_is_loading_;
00173 boost::mutex robot_model_loading_lock_;
00174
00175 moveit::tools::BackgroundProcessing background_process_;
00176 std::deque<boost::function<void()> > main_loop_jobs_;
00177 boost::mutex main_loop_jobs_lock_;
00178 boost::condition_variable main_loop_jobs_empty_condition_;
00179
00180 Ogre::SceneNode* planning_scene_node_;
00181
00182
00183 RobotStateVisualizationPtr planning_scene_robot_;
00184 PlanningSceneRenderPtr planning_scene_render_;
00185
00186 bool planning_scene_needs_render_;
00187 float current_scene_time_;
00188
00189 rviz::Property* scene_category_;
00190 rviz::Property* robot_category_;
00191
00192 rviz::StringProperty* move_group_ns_property_;
00193 rviz::StringProperty* robot_description_property_;
00194 rviz::StringProperty* scene_name_property_;
00195 rviz::BoolProperty* scene_enabled_property_;
00196 rviz::BoolProperty* scene_robot_visual_enabled_property_;
00197 rviz::BoolProperty* scene_robot_collision_enabled_property_;
00198 rviz::RosTopicProperty* planning_scene_topic_property_;
00199 rviz::FloatProperty* robot_alpha_property_;
00200 rviz::FloatProperty* scene_alpha_property_;
00201 rviz::ColorProperty* scene_color_property_;
00202 rviz::ColorProperty* attached_body_color_property_;
00203 rviz::FloatProperty* scene_display_time_property_;
00204 rviz::EnumProperty* octree_render_property_;
00205 rviz::EnumProperty* octree_coloring_property_;
00206 };
00207
00208 }
00209
00210 #endif