37 #ifndef MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_ 38 #define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_ 61 class RosTopicProperty;
79 virtual void update(
float wall_dt,
float ros_dt);
82 void setLinkColor(
const std::string& link_name,
const QColor& color);
83 void unsetLinkColor(
const std::string& link_name);
85 void queueRenderSceneGeometry();
89 void addBackgroundJob(
const boost::function<
void()>& job,
const std::string&
name);
95 void spawnBackgroundJob(
const boost::function<
void()>& job);
98 void addMainLoopJob(
const boost::function<
void()>& job);
100 void waitForAllMainLoopJobs();
105 const std::string getMoveGroupNS()
const;
106 const robot_model::RobotModelConstPtr& getRobotModel()
const;
114 const planning_scene_monitor::PlanningSceneMonitorPtr& getPlanningSceneMonitor();
121 void changedMoveGroupNS();
122 void changedRobotDescription();
123 void changedSceneName();
124 void changedSceneEnabled();
125 void changedSceneRobotVisualEnabled();
126 void changedSceneRobotCollisionEnabled();
127 void changedRobotSceneAlpha();
128 void changedSceneAlpha();
129 void changedSceneColor();
130 void changedPlanningSceneTopic();
131 void changedSceneDisplayTime();
132 void changedOctreeRenderMode();
133 void changedOctreeColorMode();
136 virtual void changedAttachedBodyColor();
145 void clearRobotModel();
149 virtual planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor();
152 virtual void onRobotModelLoaded();
157 void calculateOffsetPosition();
159 void executeMainLoopJobs();
161 void renderPlanningScene();
162 void setLinkColor(
rviz::Robot* robot,
const std::string& link_name,
const QColor& color);
163 void unsetLinkColor(
rviz::Robot* robot,
const std::string& link_name);
164 void setGroupColor(
rviz::Robot* robot,
const std::string& group_name,
const QColor& color);
165 void unsetGroupColor(
rviz::Robot* robot,
const std::string& group_name);
169 virtual void onInitialize();
170 virtual void onEnable();
171 virtual void onDisable();
172 virtual void fixedFrameChanged();
175 virtual void updateInternal(
float wall_dt,
float ros_dt);
rviz::RosTopicProperty * planning_scene_topic_property_
void loadRobotModel(urdf::ModelInterfaceSharedPtr &robot_model_out)
rviz::EnumProperty * octree_coloring_property_
rviz::EnumProperty * octree_render_property_
boost::mutex main_loop_jobs_lock_
rviz::FloatProperty * scene_display_time_property_
RobotStateVisualizationPtr planning_scene_robot_
geometry_msgs::TransformStamped t
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
boost::mutex robot_model_loading_lock_
rviz::ColorProperty * scene_color_property_
rviz::Property * scene_category_
rviz::StringProperty * move_group_ns_property_
rviz::BoolProperty * scene_robot_visual_enabled_property_
std::deque< boost::function< void()> > main_loop_jobs_
float current_scene_time_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Ogre::SceneNode * planning_scene_node_
displays planning scene with everything in it
rviz::FloatProperty * scene_alpha_property_
rviz::Property * robot_category_
rviz::ColorProperty * attached_body_color_property_
rviz::StringProperty * scene_name_property_
moveit::tools::BackgroundProcessing background_process_
rviz::FloatProperty * robot_alpha_property_
rviz::StringProperty * robot_description_property_
rviz::BoolProperty * scene_enabled_property_
boost::condition_variable main_loop_jobs_empty_condition_
rviz::BoolProperty * scene_robot_collision_enabled_property_
PlanningSceneRenderPtr planning_scene_render_
bool planning_scene_needs_render_