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