Go to the documentation of this file.
60 class RosTopicProperty;
78 void update(
float wall_dt,
float ros_dt)
override;
79 void reset()
override;
81 void setLinkColor(
const std::string& link_name,
const QColor& color);
105 const moveit::core::RobotModelConstPtr&
getRobotModel()
const;
rviz::StringProperty * move_group_ns_property_
void changedSceneRobotVisualEnabled()
virtual void onRobotModelLoaded()
This is an event called by loadRobotModel() in the MainLoop; do not call directly.
rviz::EnumProperty * octree_coloring_property_
void calculateOffsetPosition()
Set the scene node's position, given the target frame and the planning frame.
rviz::StringProperty * robot_description_property_
void fixedFrameChanged() override
rviz::Property * robot_category_
void changedPlanningSceneTopic()
virtual void updateInternal(float wall_dt, float ros_dt)
rviz::BoolProperty * scene_robot_collision_enabled_property_
void changedOctreeRendering()
void setSceneName(const QString &name)
boost::mutex main_loop_jobs_lock_
bool waitForCurrentRobotState(const ros::Time &t=ros::Time::now())
wait for robot state more recent than t
rviz::ColorProperty * scene_color_property_
void changedSceneRobotCollisionEnabled()
void onDisable() override
rviz::Property * scene_category_
rviz::StringProperty * scene_name_property_
void update(float wall_dt, float ros_dt) override
~PlanningSceneDisplay() override
PlanningSceneDisplay(bool listen_to_planning_scene=true, bool show_scene_robot=true)
rviz::EnumProperty * octree_render_property_
void changedRobotDescription()
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor()
bool robot_state_needs_render_
virtual void clearRobotModel()
void addMainLoopJob(const boost::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
const std::string getMoveGroupNS() const
void waitForAllMainLoopJobs()
rviz::BoolProperty * scene_enabled_property_
void onInitialize() override
void executeMainLoopJobs()
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
float current_scene_time_
virtual planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor()
std::deque< boost::function< void()> > main_loop_jobs_
rviz::ColorProperty * attached_body_color_property_
void unsetLinkColor(const std::string &link_name)
RobotStateVisualizationPtr planning_scene_robot_
void unsetAllColors(rviz::Robot *robot)
void changedMoveGroupNS()
Ogre::SceneNode * planning_scene_node_
displays planning scene with everything in it
void spawnBackgroundJob(const boost::function< void()> &job)
void unsetGroupColor(rviz::Robot *robot, const std::string &group_name)
void changedSceneDisplayTime()
void addBackgroundJob(const boost::function< void()> &job, const std::string &name)
boost::condition_variable main_loop_jobs_empty_condition_
virtual void changedAttachedBodyColor()
rviz::FloatProperty * robot_alpha_property_
void setGroupColor(rviz::Robot *robot, const std::string &group_name, const QColor &color)
moveit::tools::BackgroundProcessing background_process_
rviz::FloatProperty * scene_alpha_property_
void clearJobs()
remove all queued jobs
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
rviz::FloatProperty * scene_display_time_property_
PlanningSceneRenderPtr planning_scene_render_
virtual void onNewPlanningSceneState()
This is called upon successful retrieval of the (initial) planning scene state.
const moveit::core::RobotModelConstPtr & getRobotModel() const
boost::mutex robot_model_loading_lock_
rviz::BoolProperty * scene_robot_visual_enabled_property_
virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
void renderPlanningScene()
void changedSceneEnabled()
rviz::RosTopicProperty * planning_scene_topic_property_
void setLinkColor(const std::string &link_name, const QColor &color)
bool planning_scene_needs_render_
void save(rviz::Config config) const override
void load(const rviz::Config &config) override
void changedRobotSceneAlpha()
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW()
get write access to planning scene
void queueRenderSceneGeometry()
visualization
Author(s): Ioan Sucan
, Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:26