Signals | Public Member Functions | Public Attributes | Protected Types | Protected Member Functions | Protected Attributes | Private Slots | List of all members
moveit_rviz_plugin::MotionPlanningDisplay Class Reference

#include <motion_planning_display.h>

Inheritance diagram for moveit_rviz_plugin::MotionPlanningDisplay:
Inheritance graph
[legend]

Signals

void queryGoalStateChanged ()
 
void queryStartStateChanged ()
 
- Signals inherited from rviz::Display
void timeSignal (ros::Time time, QPrivateSignal)
 
- Signals inherited from rviz::Property
void aboutToChange ()
 
void changed ()
 
void childListChanged (Property *this_property)
 

Public Member Functions

void addStatusText (const std::string &text)
 
void addStatusText (const std::vector< std::string > &text)
 
void changePlanningGroup (const std::string &group)
 
void clearPlaceLocationsDisplay ()
 
void dropVisualizedTrajectory ()
 
std::string getCurrentPlanningGroup () const
 
const moveit::core::RobotStategetPreviousState () const
 
moveit::core::RobotStateConstPtr getQueryGoalState () const
 
const robot_interaction::InteractionHandlerPtr & getQueryGoalStateHandler () const
 
moveit::core::RobotStateConstPtr getQueryStartState () const
 
const robot_interaction::InteractionHandlerPtr & getQueryStartStateHandler () const
 
const robot_interaction::RobotInteractionPtr & getRobotInteraction () const
 
void load (const rviz::Config &config) override
 
 MotionPlanningDisplay ()
 
void rememberPreviousStartState ()
 
void reset () override
 
void resetStatusTextColor ()
 
void save (rviz::Config config) const override
 
void setName (const QString &name) override
 
void setQueryGoalState (const moveit::core::RobotState &goal)
 
void setQueryStartState (const moveit::core::RobotState &start)
 
void setStatusTextColor (const QColor &color)
 
void toggleSelectPlanningGroupSubscription (bool enable)
 
void update (float wall_dt, float ros_dt) override
 
void updateQueryGoalState ()
 
void updateQueryStartState ()
 
void updateQueryStates (const moveit::core::RobotState &current_state)
 
void useApproximateIK (bool flag)
 
void visualizePlaceLocations (const std::vector< geometry_msgs::PoseStamped > &place_poses)
 
 ~MotionPlanningDisplay () override
 
- Public Member Functions inherited from moveit_rviz_plugin::PlanningSceneDisplay
void addBackgroundJob (const boost::function< void()> &job, const std::string &name)
 
void addMainLoopJob (const boost::function< void()> &job)
 queue the execution of this function for the next time the main update() loop gets called More...
 
void clearJobs ()
 remove all queued jobs More...
 
const std::string getMoveGroupNS () const
 
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor ()
 
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO () const
 get read-only access to planning scene More...
 
planning_scene_monitor::LockedPlanningSceneRW getPlanningSceneRW ()
 get write access to planning scene More...
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
void load (const rviz::Config &config) override
 
 PlanningSceneDisplay (bool listen_to_planning_scene=true, bool show_scene_robot=true)
 
void queueRenderSceneGeometry ()
 
void reset () override
 
void save (rviz::Config config) const override
 
void setLinkColor (const std::string &link_name, const QColor &color)
 
void spawnBackgroundJob (const boost::function< void()> &job)
 
void unsetLinkColor (const std::string &link_name)
 
void update (float wall_dt, float ros_dt) override
 
void waitForAllMainLoopJobs ()
 
bool waitForCurrentRobotState (const ros::Time &t=ros::Time::now())
 wait for robot state more recent than t More...
 
 ~PlanningSceneDisplay () override
 
- Public Member Functions inherited from rviz::Display
virtual void deleteStatus (const QString &name)
 
void deleteStatusStd (const std::string &name)
 
 Display ()
 
void emitTimeSignal (ros::Time time)
 
QWidget * getAssociatedWidget () const
 
PanelDockWidgetgetAssociatedWidgetPanel ()
 
virtual QString getClassId () const
 
Ogre::SceneNode * getSceneNode () const
 
QVariant getViewData (int column, int role) const override
 
Qt::ItemFlags getViewFlags (int column) const override
 
uint32_t getVisibilityBits ()
 
void initialize (DisplayContext *context)
 
bool isEnabled () const
 
void setAssociatedWidget (QWidget *widget)
 
virtual void setClassId (const QString &class_id)
 
void setFixedFrame (const QString &fixed_frame)
 
virtual void setStatus (StatusProperty::Level level, const QString &name, const QString &text)
 
void setStatusStd (StatusProperty::Level level, const std::string &name, const std::string &text)
 
virtual void setTopic (const QString &topic, const QString &datatype)
 
void setVisibilityBits (uint32_t bits)
 
void unsetVisibilityBits (uint32_t bits)
 
 ~Display () override
 
- Public Member Functions inherited from rviz::BoolProperty
 BoolProperty (const QString &name, bool default_value, const QString &description, P *parent, Func &&changed_slot)
 
 BoolProperty (const QString &name, bool default_value, const QString &description, Property *parent, Func &&changed_slot, const R *receiver)
 
 BoolProperty (const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr)
 
virtual bool getBool () const
 
bool getDisableChildren () override
 
bool getDisableChildrenIfFalse ()
 
void setDisableChildrenIfFalse (bool disable)
 
 ~BoolProperty () override
 
- Public Member Functions inherited from rviz::Property
virtual void addChild (Property *child, int index=-1)
 
PropertychildAt (int index) const
 
virtual PropertychildAtUnchecked (int index) const
 
virtual void collapse ()
 
std::enable_if<!QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type connect (const QObject *context, Func &&slot, Qt::ConnectionType type=Qt::AutoConnection)
 
QMetaObject::Connection connect (const QObject *receiver, const char *slot, Qt::ConnectionType type=Qt::AutoConnection)
 
std::enable_if< QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type connect (const R *receiver, Func &&slot, Qt::ConnectionType type=Qt::AutoConnection)
 
std::enable_if<!QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type connect (Func &&slot, Qt::ConnectionType type=Qt::AutoConnection)
 
bool contains (Property *possible_child) const
 
virtual QWidget * createEditor (QWidget *parent, const QStyleOptionViewItem &option)
 
virtual void expand ()
 
virtual QString getDescription () const
 
virtual bool getHidden () const
 
virtual QIcon getIcon () const
 
PropertyTreeModelgetModel () const
 
virtual QString getName () const
 
std::string getNameStd () const
 
PropertygetParent () const
 
virtual bool getReadOnly () const
 
virtual QVariant getValue () const
 
void hide ()
 
void insertChildSorted (Property *child)
 
bool isAncestorOf (Property *possible_child) const
 
virtual void moveChild (int from_index, int to_index)
 
virtual int numChildren () const
 
virtual bool paint (QPainter *painter, const QStyleOptionViewItem &option) const
 
 Property (const QString &name, const QVariant &default_value, const QString &description, P *parent, Func &&changed_slot)
 
 Property (const QString &name, const QVariant &default_value, const QString &description, Property *parent, Func &&changed_slot, const R *receiver)
 
 Property (const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr)
 
virtual void removeChildren (int start_index=0, int count=-1)
 
int rowNumberInParent () const
 
virtual void setDescription (const QString &description)
 
virtual void setHidden (bool hidden)
 
virtual void setIcon (const QIcon &icon)
 
void setModel (PropertyTreeModel *model)
 
void setParent (Property *new_parent)
 
virtual void setReadOnly (bool read_only)
 
void setShouldBeSaved (bool save)
 
virtual bool setValue (const QVariant &new_value)
 
bool shouldBeSaved () const
 
void show ()
 
virtual PropertysubProp (const QString &sub_name)
 
PropertytakeChild (Property *child)
 
virtual PropertytakeChildAt (int index)
 
 ~Property () override
 

Public Attributes

std::vector< std::shared_ptr< rviz::Shape > > place_locations_display_
 

Protected Types

enum  LinkDisplayStatus { COLLISION_LINK, OUTSIDE_BOUNDS_LINK }
 

Protected Member Functions

void backgroundJobUpdate (moveit::tools::BackgroundProcessing::JobEvent event, const std::string &jobname)
 
void clearRobotModel () override
 
void computeMetrics (bool start, const std::string &group, double payload)
 
void computeMetricsInternal (std::map< std::string, double > &metrics, const robot_interaction::EndEffectorInteraction &eef, const moveit::core::RobotState &state, double payload)
 
void displayMetrics (bool start)
 
void displayTable (const std::map< std::string, double > &values, const Ogre::ColourValue &color, const Ogre::Vector3 &pos, const Ogre::Quaternion &orient)
 
void drawQueryGoalState ()
 
void drawQueryStartState ()
 
void executeMainLoopJobs ()
 
void fixedFrameChanged () override
 
bool isIKSolutionCollisionFree (moveit::core::RobotState *state, const moveit::core::JointModelGroup *group, const double *ik_solution) const
 
void onDisable () override
 
void onEnable () override
 
void onInitialize () override
 
void onNewPlanningSceneState () override
 This is called upon successful retrieval of the (initial) planning scene state. More...
 
void onRobotModelLoaded () override
 This is an event called by loadRobotModel() in the MainLoop; do not call directly. More...
 
void onSceneMonitorReceivedUpdate (planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type) override
 
void populateMenuHandler (std::shared_ptr< interactive_markers::MenuHandler > &mh)
 
void publishInteractiveMarkers (bool pose_update)
 
void recomputeQueryGoalStateMetrics ()
 
void recomputeQueryStartStateMetrics ()
 
void renderWorkspaceBox ()
 
void scheduleDrawQueryGoalState (robot_interaction::InteractionHandler *handler, bool error_state_changed)
 
void scheduleDrawQueryStartState (robot_interaction::InteractionHandler *handler, bool error_state_changed)
 
void selectPlanningGroupCallback (const std_msgs::StringConstPtr &msg)
 
void setQueryStateHelper (bool use_start_state, const std::string &v)
 
void updateBackgroundJobProgressBar ()
 
void updateInternal (float wall_dt, float ros_dt) override
 
void updateLinkColors ()
 
void updateStateExceptModified (moveit::core::RobotState &dest, const moveit::core::RobotState &src)
 
- Protected Member Functions inherited from moveit_rviz_plugin::PlanningSceneDisplay
void calculateOffsetPosition ()
 Set the scene node's position, given the target frame and the planning frame. More...
 
virtual planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor ()
 
void executeMainLoopJobs ()
 
void fixedFrameChanged () override
 
void loadRobotModel ()
 
void onDisable () override
 
void onEnable () override
 
void onInitialize () override
 
void renderPlanningScene ()
 
void setGroupColor (rviz::Robot *robot, const std::string &group_name, const QColor &color)
 
void setLinkColor (rviz::Robot *robot, const std::string &link_name, const QColor &color)
 
void unsetAllColors (rviz::Robot *robot)
 
void unsetGroupColor (rviz::Robot *robot, const std::string &group_name)
 
void unsetLinkColor (rviz::Robot *robot, const std::string &link_name)
 
- Protected Member Functions inherited from rviz::Display
virtual void clearStatuses ()
 
bool initialized () const
 
- Protected Member Functions inherited from rviz::Property
void loadValue (const Config &config)
 

Protected Attributes

rviz::BoolPropertycompute_weight_limit_property_
 
std::map< std::pair< bool, std::string >, std::map< std::string, double > > computed_metrics_
 
std::map< std::string, dynamics_solver::DynamicsSolverPtr > dynamics_solver_
 
MotionPlanningFrameframe_
 
rviz::PanelDockWidgetframe_dock_
 
rviz::Displayint_marker_display_
 
kinematics_metrics::KinematicsMetricsPtr kinematics_metrics_
 
std::shared_ptr< interactive_markers::MenuHandlermenu_handler_goal_
 
std::shared_ptr< interactive_markers::MenuHandlermenu_handler_start_
 
rviz::Propertymetrics_category_
 
rviz::FloatPropertymetrics_set_payload_property_
 
rviz::FloatPropertymetrics_text_height_property_
 
std::set< std::string > modified_groups_
 
ros::NodeHandle node_handle_
 
rviz::Propertypath_category_
 
rviz::Propertyplan_category_
 
rviz::EnumPropertyplanning_group_property_
 
ros::Subscriber planning_group_sub_
 
std::map< std::string, bool > position_only_ik_
 Some groups use position only ik, calls to the metrics have to be modified appropriately. More...
 
moveit::core::RobotStatePtr previous_state_
 remember previous start state (updated before starting execution) More...
 
ros::NodeHandle private_handle_
 
rviz::ColorPropertyquery_colliding_link_color_property_
 
rviz::FloatPropertyquery_goal_alpha_property_
 
rviz::ColorPropertyquery_goal_color_property_
 
robot_interaction::InteractionHandlerPtr query_goal_state_
 
rviz::BoolPropertyquery_goal_state_property_
 
rviz::FloatPropertyquery_marker_scale_property_
 
rviz::ColorPropertyquery_outside_joint_limits_link_color_property_
 
RobotStateVisualizationPtr query_robot_goal_
 Handles drawing the robot at the goal configuration. More...
 
RobotStateVisualizationPtr query_robot_start_
 Handles drawing the robot at the start configuration. More...
 
rviz::FloatPropertyquery_start_alpha_property_
 
rviz::ColorPropertyquery_start_color_property_
 
robot_interaction::InteractionHandlerPtr query_start_state_
 
rviz::BoolPropertyquery_start_state_property_
 
robot_interaction::RobotInteractionPtr robot_interaction_
 
rviz::BoolPropertyshow_joint_torques_property_
 
rviz::BoolPropertyshow_manipulability_index_property_
 
rviz::BoolPropertyshow_manipulability_property_
 
rviz::BoolPropertyshow_workspace_property_
 
std::map< std::string, LinkDisplayStatusstatus_links_goal_
 
std::map< std::string, LinkDisplayStatusstatus_links_start_
 
bool text_display_for_start_
 indicates whether the text display is for the start state or not More...
 
Ogre::SceneNode * text_display_scene_node_
 displays texts More...
 
rviz::MovableTexttext_to_display_
 
TrajectoryVisualizationPtr trajectory_visual_
 
boost::mutex update_metrics_lock_
 
std::unique_ptr< rviz::Shapeworkspace_box_
 
- Protected Attributes inherited from moveit_rviz_plugin::PlanningSceneDisplay
rviz::ColorPropertyattached_body_color_property_
 
moveit::tools::BackgroundProcessing background_process_
 
float current_scene_time_
 
std::deque< boost::function< void()> > main_loop_jobs_
 
boost::condition_variable main_loop_jobs_empty_condition_
 
boost::mutex main_loop_jobs_lock_
 
rviz::StringPropertymove_group_ns_property_
 
rviz::EnumPropertyoctree_coloring_property_
 
rviz::EnumPropertyoctree_render_property_
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
bool planning_scene_needs_render_
 
Ogre::SceneNode * planning_scene_node_
 displays planning scene with everything in it More...
 
PlanningSceneRenderPtr planning_scene_render_
 
RobotStateVisualizationPtr planning_scene_robot_
 
rviz::RosTopicPropertyplanning_scene_topic_property_
 
rviz::FloatPropertyrobot_alpha_property_
 
rviz::Propertyrobot_category_
 
rviz::StringPropertyrobot_description_property_
 
boost::mutex robot_model_loading_lock_
 
bool robot_state_needs_render_
 
rviz::FloatPropertyscene_alpha_property_
 
rviz::Propertyscene_category_
 
rviz::ColorPropertyscene_color_property_
 
rviz::FloatPropertyscene_display_time_property_
 
rviz::BoolPropertyscene_enabled_property_
 
rviz::StringPropertyscene_name_property_
 
rviz::BoolPropertyscene_robot_collision_enabled_property_
 
rviz::BoolPropertyscene_robot_visual_enabled_property_
 
- Protected Attributes inherited from rviz::Display
DisplayContextcontext_
 
QString fixed_frame_
 
Ogre::SceneManager * scene_manager_
 
Ogre::SceneNode * scene_node_
 
ros::NodeHandle threaded_nh_
 
ros::NodeHandle update_nh_
 
- Protected Attributes inherited from rviz::Property
bool child_indexes_valid_
 
QIcon icon_
 
PropertyTreeModelmodel_
 
QVariant value_
 

Private Slots

void changedAttachedBodyColor () override
 
void changedMetricsSetPayload ()
 
void changedMetricsTextHeight ()
 
void changedPlanningGroup ()
 
void changedQueryCollidingLinkColor ()
 
void changedQueryGoalAlpha ()
 
void changedQueryGoalColor ()
 
void changedQueryGoalState ()
 
void changedQueryJointViolationColor ()
 
void changedQueryMarkerScale ()
 
void changedQueryStartAlpha ()
 
void changedQueryStartColor ()
 
void changedQueryStartState ()
 
void changedShowJointTorques ()
 
void changedShowManipulability ()
 
void changedShowManipulabilityIndex ()
 
void changedShowWeightLimit ()
 
void changedWorkspace ()
 
void motionPanelVisibilityChange (bool enable)
 
void resetInteractiveMarkers ()
 

Additional Inherited Members

- Public Slots inherited from rviz::Display
virtual void onEnableChanged ()
 
void queueRender ()
 
void setEnabled (bool enabled)
 
void setIcon (const QIcon &icon) override
 
- Public Slots inherited from rviz::BoolProperty
bool setBool (bool value)
 
- Protected Slots inherited from moveit_rviz_plugin::PlanningSceneDisplay
virtual void changedAttachedBodyColor ()
 

Detailed Description

Definition at line 82 of file motion_planning_display.h.

Member Enumeration Documentation

◆ LinkDisplayStatus

Enumerator
COLLISION_LINK 
OUTSIDE_BOUNDS_LINK 

Definition at line 193 of file motion_planning_display.h.

Constructor & Destructor Documentation

◆ MotionPlanningDisplay()

moveit_rviz_plugin::MotionPlanningDisplay::MotionPlanningDisplay ( )

Definition at line 114 of file motion_planning_display.cpp.

◆ ~MotionPlanningDisplay()

moveit_rviz_plugin::MotionPlanningDisplay::~MotionPlanningDisplay ( )
override

Definition at line 217 of file motion_planning_display.cpp.

Member Function Documentation

◆ addStatusText() [1/2]

void moveit_rviz_plugin::MotionPlanningDisplay::addStatusText ( const std::string &  text)

Definition at line 718 of file motion_planning_display.cpp.

◆ addStatusText() [2/2]

void moveit_rviz_plugin::MotionPlanningDisplay::addStatusText ( const std::vector< std::string > &  text)

Definition at line 724 of file motion_planning_display.cpp.

◆ backgroundJobUpdate()

void moveit_rviz_plugin::MotionPlanningDisplay::backgroundJobUpdate ( moveit::tools::BackgroundProcessing::JobEvent  event,
const std::string &  jobname 
)
protected

Definition at line 358 of file motion_planning_display.cpp.

◆ changedAttachedBodyColor

void moveit_rviz_plugin::MotionPlanningDisplay::changedAttachedBodyColor ( )
overrideprivateslot

Definition at line 925 of file motion_planning_display.cpp.

◆ changedMetricsSetPayload

void moveit_rviz_plugin::MotionPlanningDisplay::changedMetricsSetPayload ( )
privateslot

Definition at line 447 of file motion_planning_display.cpp.

◆ changedMetricsTextHeight

void moveit_rviz_plugin::MotionPlanningDisplay::changedMetricsTextHeight ( )
privateslot

Definition at line 461 of file motion_planning_display.cpp.

◆ changedPlanningGroup

void moveit_rviz_plugin::MotionPlanningDisplay::changedPlanningGroup ( )
privateslot

Definition at line 1054 of file motion_planning_display.cpp.

◆ changedQueryCollidingLinkColor

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryCollidingLinkColor ( )
privateslot

Definition at line 913 of file motion_planning_display.cpp.

◆ changedQueryGoalAlpha

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryGoalAlpha ( )
privateslot

Definition at line 907 of file motion_planning_display.cpp.

◆ changedQueryGoalColor

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryGoalColor ( )
privateslot

Definition at line 895 of file motion_planning_display.cpp.

◆ changedQueryGoalState

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryGoalState ( )
privateslot

Definition at line 754 of file motion_planning_display.cpp.

◆ changedQueryJointViolationColor

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryJointViolationColor ( )
privateslot

Definition at line 919 of file motion_planning_display.cpp.

◆ changedQueryMarkerScale

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryMarkerScale ( )
privateslot

Definition at line 883 of file motion_planning_display.cpp.

◆ changedQueryStartAlpha

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryStartAlpha ( )
privateslot

Definition at line 877 of file motion_planning_display.cpp.

◆ changedQueryStartColor

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryStartColor ( )
privateslot

Definition at line 865 of file motion_planning_display.cpp.

◆ changedQueryStartState

void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryStartState ( )
privateslot

Definition at line 744 of file motion_planning_display.cpp.

◆ changedShowJointTorques

void moveit_rviz_plugin::MotionPlanningDisplay::changedShowJointTorques ( )
privateslot

Definition at line 433 of file motion_planning_display.cpp.

◆ changedShowManipulability

void moveit_rviz_plugin::MotionPlanningDisplay::changedShowManipulability ( )
privateslot

Definition at line 419 of file motion_planning_display.cpp.

◆ changedShowManipulabilityIndex

void moveit_rviz_plugin::MotionPlanningDisplay::changedShowManipulabilityIndex ( )
privateslot

Definition at line 405 of file motion_planning_display.cpp.

◆ changedShowWeightLimit

void moveit_rviz_plugin::MotionPlanningDisplay::changedShowWeightLimit ( )
privateslot

Definition at line 391 of file motion_planning_display.cpp.

◆ changedWorkspace

void moveit_rviz_plugin::MotionPlanningDisplay::changedWorkspace ( )
privateslot

Definition at line 1078 of file motion_planning_display.cpp.

◆ changePlanningGroup()

void moveit_rviz_plugin::MotionPlanningDisplay::changePlanningGroup ( const std::string &  group)

Definition at line 1041 of file motion_planning_display.cpp.

◆ clearPlaceLocationsDisplay()

void moveit_rviz_plugin::MotionPlanningDisplay::clearPlaceLocationsDisplay ( )

Definition at line 1473 of file motion_planning_display.cpp.

◆ clearRobotModel()

void moveit_rviz_plugin::MotionPlanningDisplay::clearRobotModel ( )
overrideprotectedvirtual

This function is used by loadRobotModel() and should only be called in the MainLoop You probably should not call this function directly

Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.

Definition at line 1155 of file motion_planning_display.cpp.

◆ computeMetrics()

void moveit_rviz_plugin::MotionPlanningDisplay::computeMetrics ( bool  start,
const std::string &  group,
double  payload 
)
protected

Definition at line 512 of file motion_planning_display.cpp.

◆ computeMetricsInternal()

void moveit_rviz_plugin::MotionPlanningDisplay::computeMetricsInternal ( std::map< std::string, double > &  metrics,
const robot_interaction::EndEffectorInteraction eef,
const moveit::core::RobotState state,
double  payload 
)
protected

Definition at line 527 of file motion_planning_display.cpp.

◆ displayMetrics()

void moveit_rviz_plugin::MotionPlanningDisplay::displayMetrics ( bool  start)
protected

Definition at line 587 of file motion_planning_display.cpp.

◆ displayTable()

void moveit_rviz_plugin::MotionPlanningDisplay::displayTable ( const std::map< std::string, double > &  values,
const Ogre::ColourValue &  color,
const Ogre::Vector3 pos,
const Ogre::Quaternion orient 
)
protected

Definition at line 466 of file motion_planning_display.cpp.

◆ drawQueryGoalState()

void moveit_rviz_plugin::MotionPlanningDisplay::drawQueryGoalState ( )
protected

Definition at line 764 of file motion_planning_display.cpp.

◆ drawQueryStartState()

void moveit_rviz_plugin::MotionPlanningDisplay::drawQueryStartState ( )
protected

Definition at line 644 of file motion_planning_display.cpp.

◆ dropVisualizedTrajectory()

void moveit_rviz_plugin::MotionPlanningDisplay::dropVisualizedTrajectory ( )
inline

Definition at line 129 of file motion_planning_display.h.

◆ executeMainLoopJobs()

void moveit_rviz_plugin::MotionPlanningDisplay::executeMainLoopJobs ( )
protected

◆ fixedFrameChanged()

void moveit_rviz_plugin::MotionPlanningDisplay::fixedFrameChanged ( )
overrideprotectedvirtual

Reimplemented from rviz::Display.

Definition at line 1464 of file motion_planning_display.cpp.

◆ getCurrentPlanningGroup()

std::string moveit_rviz_plugin::MotionPlanningDisplay::getCurrentPlanningGroup ( ) const

Definition at line 1083 of file motion_planning_display.cpp.

◆ getPreviousState()

const moveit::core::RobotState& moveit_rviz_plugin::MotionPlanningDisplay::getPreviousState ( ) const
inline

Definition at line 109 of file motion_planning_display.h.

◆ getQueryGoalState()

moveit::core::RobotStateConstPtr moveit_rviz_plugin::MotionPlanningDisplay::getQueryGoalState ( ) const
inline

Definition at line 104 of file motion_planning_display.h.

◆ getQueryGoalStateHandler()

const robot_interaction::InteractionHandlerPtr& moveit_rviz_plugin::MotionPlanningDisplay::getQueryGoalStateHandler ( ) const
inline

Definition at line 124 of file motion_planning_display.h.

◆ getQueryStartState()

moveit::core::RobotStateConstPtr moveit_rviz_plugin::MotionPlanningDisplay::getQueryStartState ( ) const
inline

Definition at line 99 of file motion_planning_display.h.

◆ getQueryStartStateHandler()

const robot_interaction::InteractionHandlerPtr& moveit_rviz_plugin::MotionPlanningDisplay::getQueryStartStateHandler ( ) const
inline

Definition at line 119 of file motion_planning_display.h.

◆ getRobotInteraction()

const robot_interaction::RobotInteractionPtr& moveit_rviz_plugin::MotionPlanningDisplay::getRobotInteraction ( ) const
inline

Definition at line 114 of file motion_planning_display.h.

◆ isIKSolutionCollisionFree()

bool moveit_rviz_plugin::MotionPlanningDisplay::isIKSolutionCollisionFree ( moveit::core::RobotState state,
const moveit::core::JointModelGroup group,
const double *  ik_solution 
) const
protected

Definition at line 998 of file motion_planning_display.cpp.

◆ load()

void moveit_rviz_plugin::MotionPlanningDisplay::load ( const rviz::Config config)
overridevirtual

Reimplemented from rviz::Display.

Definition at line 1367 of file motion_planning_display.cpp.

◆ motionPanelVisibilityChange

void moveit_rviz_plugin::MotionPlanningDisplay::motionPanelVisibilityChange ( bool  enable)
privateslot

Definition at line 300 of file motion_planning_display.cpp.

◆ onDisable()

void moveit_rviz_plugin::MotionPlanningDisplay::onDisable ( )
overrideprotectedvirtual

Reimplemented from rviz::Display.

Definition at line 1326 of file motion_planning_display.cpp.

◆ onEnable()

void moveit_rviz_plugin::MotionPlanningDisplay::onEnable ( )
overrideprotectedvirtual

Reimplemented from rviz::Display.

Definition at line 1305 of file motion_planning_display.cpp.

◆ onInitialize()

void moveit_rviz_plugin::MotionPlanningDisplay::onInitialize ( )
overrideprotectedvirtual

Reimplemented from rviz::Display.

Definition at line 230 of file motion_planning_display.cpp.

◆ onNewPlanningSceneState()

void moveit_rviz_plugin::MotionPlanningDisplay::onNewPlanningSceneState ( )
overrideprotectedvirtual

This is called upon successful retrieval of the (initial) planning scene state.

Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.

Definition at line 1246 of file motion_planning_display.cpp.

◆ onRobotModelLoaded()

void moveit_rviz_plugin::MotionPlanningDisplay::onRobotModelLoaded ( )
overrideprotectedvirtual

This is an event called by loadRobotModel() in the MainLoop; do not call directly.

Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.

Definition at line 1172 of file motion_planning_display.cpp.

◆ onSceneMonitorReceivedUpdate()

void moveit_rviz_plugin::MotionPlanningDisplay::onSceneMonitorReceivedUpdate ( planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType  update_type)
overrideprotectedvirtual

Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.

Definition at line 1293 of file motion_planning_display.cpp.

◆ populateMenuHandler()

void moveit_rviz_plugin::MotionPlanningDisplay::populateMenuHandler ( std::shared_ptr< interactive_markers::MenuHandler > &  mh)
protected

Definition at line 1123 of file motion_planning_display.cpp.

◆ publishInteractiveMarkers()

void moveit_rviz_plugin::MotionPlanningDisplay::publishInteractiveMarkers ( bool  pose_update)
protected

Definition at line 836 of file motion_planning_display.cpp.

◆ queryGoalStateChanged

void moveit_rviz_plugin::MotionPlanningDisplay::queryGoalStateChanged ( )
signal

◆ queryStartStateChanged

void moveit_rviz_plugin::MotionPlanningDisplay::queryStartStateChanged ( )
signal

◆ recomputeQueryGoalStateMetrics()

void moveit_rviz_plugin::MotionPlanningDisplay::recomputeQueryGoalStateMetrics ( )
protected

Definition at line 737 of file motion_planning_display.cpp.

◆ recomputeQueryStartStateMetrics()

void moveit_rviz_plugin::MotionPlanningDisplay::recomputeQueryStartStateMetrics ( )
protected

Definition at line 730 of file motion_planning_display.cpp.

◆ rememberPreviousStartState()

void moveit_rviz_plugin::MotionPlanningDisplay::rememberPreviousStartState ( )

Definition at line 969 of file motion_planning_display.cpp.

◆ renderWorkspaceBox()

void moveit_rviz_plugin::MotionPlanningDisplay::renderWorkspaceBox ( )
protected

Definition at line 489 of file motion_planning_display.cpp.

◆ reset()

void moveit_rviz_plugin::MotionPlanningDisplay::reset ( )
overridevirtual

Reimplemented from rviz::Display.

Definition at line 325 of file motion_planning_display.cpp.

◆ resetInteractiveMarkers

void moveit_rviz_plugin::MotionPlanningDisplay::resetInteractiveMarkers ( )
privateslot

Definition at line 829 of file motion_planning_display.cpp.

◆ resetStatusTextColor()

void moveit_rviz_plugin::MotionPlanningDisplay::resetStatusTextColor ( )

Definition at line 707 of file motion_planning_display.cpp.

◆ save()

void moveit_rviz_plugin::MotionPlanningDisplay::save ( rviz::Config  config) const
overridevirtual

Reimplemented from rviz::Display.

Definition at line 1433 of file motion_planning_display.cpp.

◆ scheduleDrawQueryGoalState()

void moveit_rviz_plugin::MotionPlanningDisplay::scheduleDrawQueryGoalState ( robot_interaction::InteractionHandler handler,
bool  error_state_changed 
)
protected

Definition at line 943 of file motion_planning_display.cpp.

◆ scheduleDrawQueryStartState()

void moveit_rviz_plugin::MotionPlanningDisplay::scheduleDrawQueryStartState ( robot_interaction::InteractionHandler handler,
bool  error_state_changed 
)
protected

Definition at line 933 of file motion_planning_display.cpp.

◆ selectPlanningGroupCallback()

void moveit_rviz_plugin::MotionPlanningDisplay::selectPlanningGroupCallback ( const std_msgs::StringConstPtr &  msg)
protected

Definition at line 319 of file motion_planning_display.cpp.

◆ setName()

void moveit_rviz_plugin::MotionPlanningDisplay::setName ( const QString &  name)
overridevirtual

Reimplemented from rviz::Display.

Definition at line 347 of file motion_planning_display.cpp.

◆ setQueryGoalState()

void moveit_rviz_plugin::MotionPlanningDisplay::setQueryGoalState ( const moveit::core::RobotState goal)

Definition at line 980 of file motion_planning_display.cpp.

◆ setQueryStartState()

void moveit_rviz_plugin::MotionPlanningDisplay::setQueryStartState ( const moveit::core::RobotState start)

Definition at line 974 of file motion_planning_display.cpp.

◆ setQueryStateHelper()

void moveit_rviz_plugin::MotionPlanningDisplay::setQueryStateHelper ( bool  use_start_state,
const std::string &  v 
)
protected

Definition at line 1088 of file motion_planning_display.cpp.

◆ setStatusTextColor()

void moveit_rviz_plugin::MotionPlanningDisplay::setStatusTextColor ( const QColor &  color)

Definition at line 712 of file motion_planning_display.cpp.

◆ toggleSelectPlanningGroupSubscription()

void moveit_rviz_plugin::MotionPlanningDisplay::toggleSelectPlanningGroupSubscription ( bool  enable)

Definition at line 306 of file motion_planning_display.cpp.

◆ update()

void moveit_rviz_plugin::MotionPlanningDisplay::update ( float  wall_dt,
float  ros_dt 
)
overridevirtual

Reimplemented from rviz::Display.

Definition at line 1347 of file motion_planning_display.cpp.

◆ updateBackgroundJobProgressBar()

void moveit_rviz_plugin::MotionPlanningDisplay::updateBackgroundJobProgressBar ( )
protected

Definition at line 364 of file motion_planning_display.cpp.

◆ updateInternal()

void moveit_rviz_plugin::MotionPlanningDisplay::updateInternal ( float  wall_dt,
float  ros_dt 
)
overrideprotectedvirtual

Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.

Definition at line 1357 of file motion_planning_display.cpp.

◆ updateLinkColors()

void moveit_rviz_plugin::MotionPlanningDisplay::updateLinkColors ( )
protected

Definition at line 1013 of file motion_planning_display.cpp.

◆ updateQueryGoalState()

void moveit_rviz_plugin::MotionPlanningDisplay::updateQueryGoalState ( )

Definition at line 961 of file motion_planning_display.cpp.

◆ updateQueryStartState()

void moveit_rviz_plugin::MotionPlanningDisplay::updateQueryStartState ( )

Definition at line 953 of file motion_planning_display.cpp.

◆ updateQueryStates()

void moveit_rviz_plugin::MotionPlanningDisplay::updateQueryStates ( const moveit::core::RobotState current_state)

Definition at line 1270 of file motion_planning_display.cpp.

◆ updateStateExceptModified()

void moveit_rviz_plugin::MotionPlanningDisplay::updateStateExceptModified ( moveit::core::RobotState dest,
const moveit::core::RobotState src 
)
protected

Definition at line 1251 of file motion_planning_display.cpp.

◆ useApproximateIK()

void moveit_rviz_plugin::MotionPlanningDisplay::useApproximateIK ( bool  flag)

Definition at line 986 of file motion_planning_display.cpp.

◆ visualizePlaceLocations()

void moveit_rviz_plugin::MotionPlanningDisplay::visualizePlaceLocations ( const std::vector< geometry_msgs::PoseStamped > &  place_poses)

Definition at line 1480 of file motion_planning_display.cpp.

Member Data Documentation

◆ compute_weight_limit_property_

rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::compute_weight_limit_property_
protected

Definition at line 306 of file motion_planning_display.h.

◆ computed_metrics_

std::map<std::pair<bool, std::string>, std::map<std::string, double> > moveit_rviz_plugin::MotionPlanningDisplay::computed_metrics_
protected

The metrics are pairs of name-value for each of the active end effectors, for both start & goal states. computed_metrics_[std::make_pair(IS_START_STATE, GROUP_NAME)] = a map of key-value pairs

Definition at line 278 of file motion_planning_display.h.

◆ dynamics_solver_

std::map<std::string, dynamics_solver::DynamicsSolverPtr> moveit_rviz_plugin::MotionPlanningDisplay::dynamics_solver_
protected

Definition at line 284 of file motion_planning_display.h.

◆ frame_

MotionPlanningFrame* moveit_rviz_plugin::MotionPlanningDisplay::frame_
protected

Definition at line 258 of file motion_planning_display.h.

◆ frame_dock_

rviz::PanelDockWidget* moveit_rviz_plugin::MotionPlanningDisplay::frame_dock_
protected

Definition at line 259 of file motion_planning_display.h.

◆ int_marker_display_

rviz::Display* moveit_rviz_plugin::MotionPlanningDisplay::int_marker_display_
protected

Definition at line 314 of file motion_planning_display.h.

◆ kinematics_metrics_

kinematics_metrics::KinematicsMetricsPtr moveit_rviz_plugin::MotionPlanningDisplay::kinematics_metrics_
protected

Definition at line 283 of file motion_planning_display.h.

◆ menu_handler_goal_

std::shared_ptr<interactive_markers::MenuHandler> moveit_rviz_plugin::MotionPlanningDisplay::menu_handler_goal_
protected

Definition at line 266 of file motion_planning_display.h.

◆ menu_handler_start_

std::shared_ptr<interactive_markers::MenuHandler> moveit_rviz_plugin::MotionPlanningDisplay::menu_handler_start_
protected

Definition at line 265 of file motion_planning_display.h.

◆ metrics_category_

rviz::Property* moveit_rviz_plugin::MotionPlanningDisplay::metrics_category_
protected

Definition at line 293 of file motion_planning_display.h.

◆ metrics_set_payload_property_

rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::metrics_set_payload_property_
protected

Definition at line 310 of file motion_planning_display.h.

◆ metrics_text_height_property_

rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::metrics_text_height_property_
protected

Definition at line 311 of file motion_planning_display.h.

◆ modified_groups_

std::set<std::string> moveit_rviz_plugin::MotionPlanningDisplay::modified_groups_
protected

Hold the names of the groups for which the query states have been updated (and should not be altered when new info is received from the planning scene)

Definition at line 274 of file motion_planning_display.h.

◆ node_handle_

ros::NodeHandle moveit_rviz_plugin::MotionPlanningDisplay::node_handle_
protected

Definition at line 252 of file motion_planning_display.h.

◆ path_category_

rviz::Property* moveit_rviz_plugin::MotionPlanningDisplay::path_category_
protected

Definition at line 291 of file motion_planning_display.h.

◆ place_locations_display_

std::vector<std::shared_ptr<rviz::Shape> > moveit_rviz_plugin::MotionPlanningDisplay::place_locations_display_

Definition at line 147 of file motion_planning_display.h.

◆ plan_category_

rviz::Property* moveit_rviz_plugin::MotionPlanningDisplay::plan_category_
protected

Definition at line 292 of file motion_planning_display.h.

◆ planning_group_property_

rviz::EnumProperty* moveit_rviz_plugin::MotionPlanningDisplay::planning_group_property_
protected

Definition at line 295 of file motion_planning_display.h.

◆ planning_group_sub_

ros::Subscriber moveit_rviz_plugin::MotionPlanningDisplay::planning_group_sub_
protected

Definition at line 251 of file motion_planning_display.h.

◆ position_only_ik_

std::map<std::string, bool> moveit_rviz_plugin::MotionPlanningDisplay::position_only_ik_
protected

Some groups use position only ik, calls to the metrics have to be modified appropriately.

Definition at line 280 of file motion_planning_display.h.

◆ previous_state_

moveit::core::RobotStatePtr moveit_rviz_plugin::MotionPlanningDisplay::previous_state_
protected

remember previous start state (updated before starting execution)

Definition at line 270 of file motion_planning_display.h.

◆ private_handle_

ros::NodeHandle moveit_rviz_plugin::MotionPlanningDisplay::private_handle_
protected

Definition at line 252 of file motion_planning_display.h.

◆ query_colliding_link_color_property_

rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_colliding_link_color_property_
protected

Definition at line 303 of file motion_planning_display.h.

◆ query_goal_alpha_property_

rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_goal_alpha_property_
protected

Definition at line 302 of file motion_planning_display.h.

◆ query_goal_color_property_

rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_goal_color_property_
protected

Definition at line 300 of file motion_planning_display.h.

◆ query_goal_state_

robot_interaction::InteractionHandlerPtr moveit_rviz_plugin::MotionPlanningDisplay::query_goal_state_
protected

Definition at line 264 of file motion_planning_display.h.

◆ query_goal_state_property_

rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_goal_state_property_
protected

Definition at line 297 of file motion_planning_display.h.

◆ query_marker_scale_property_

rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_marker_scale_property_
protected

Definition at line 298 of file motion_planning_display.h.

◆ query_outside_joint_limits_link_color_property_

rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_outside_joint_limits_link_color_property_
protected

Definition at line 304 of file motion_planning_display.h.

◆ query_robot_goal_

RobotStateVisualizationPtr moveit_rviz_plugin::MotionPlanningDisplay::query_robot_goal_
protected

Handles drawing the robot at the goal configuration.

Definition at line 245 of file motion_planning_display.h.

◆ query_robot_start_

RobotStateVisualizationPtr moveit_rviz_plugin::MotionPlanningDisplay::query_robot_start_
protected

Handles drawing the robot at the start configuration.

Definition at line 244 of file motion_planning_display.h.

◆ query_start_alpha_property_

rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_start_alpha_property_
protected

Definition at line 301 of file motion_planning_display.h.

◆ query_start_color_property_

rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_start_color_property_
protected

Definition at line 299 of file motion_planning_display.h.

◆ query_start_state_

robot_interaction::InteractionHandlerPtr moveit_rviz_plugin::MotionPlanningDisplay::query_start_state_
protected

Definition at line 263 of file motion_planning_display.h.

◆ query_start_state_property_

rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_start_state_property_
protected

Definition at line 296 of file motion_planning_display.h.

◆ robot_interaction_

robot_interaction::RobotInteractionPtr moveit_rviz_plugin::MotionPlanningDisplay::robot_interaction_
protected

Definition at line 262 of file motion_planning_display.h.

◆ show_joint_torques_property_

rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::show_joint_torques_property_
protected

Definition at line 309 of file motion_planning_display.h.

◆ show_manipulability_index_property_

rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::show_manipulability_index_property_
protected

Definition at line 307 of file motion_planning_display.h.

◆ show_manipulability_property_

rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::show_manipulability_property_
protected

Definition at line 308 of file motion_planning_display.h.

◆ show_workspace_property_

rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::show_workspace_property_
protected

Definition at line 312 of file motion_planning_display.h.

◆ status_links_goal_

std::map<std::string, LinkDisplayStatus> moveit_rviz_plugin::MotionPlanningDisplay::status_links_goal_
protected

Definition at line 268 of file motion_planning_display.h.

◆ status_links_start_

std::map<std::string, LinkDisplayStatus> moveit_rviz_plugin::MotionPlanningDisplay::status_links_start_
protected

Definition at line 267 of file motion_planning_display.h.

◆ text_display_for_start_

bool moveit_rviz_plugin::MotionPlanningDisplay::text_display_for_start_
protected

indicates whether the text display is for the start state or not

Definition at line 248 of file motion_planning_display.h.

◆ text_display_scene_node_

Ogre::SceneNode* moveit_rviz_plugin::MotionPlanningDisplay::text_display_scene_node_
protected

displays texts

Definition at line 247 of file motion_planning_display.h.

◆ text_to_display_

rviz::MovableText* moveit_rviz_plugin::MotionPlanningDisplay::text_to_display_
protected

Definition at line 249 of file motion_planning_display.h.

◆ trajectory_visual_

TrajectoryVisualizationPtr moveit_rviz_plugin::MotionPlanningDisplay::trajectory_visual_
protected

Definition at line 288 of file motion_planning_display.h.

◆ update_metrics_lock_

boost::mutex moveit_rviz_plugin::MotionPlanningDisplay::update_metrics_lock_
protected

Definition at line 285 of file motion_planning_display.h.

◆ workspace_box_

std::unique_ptr<rviz::Shape> moveit_rviz_plugin::MotionPlanningDisplay::workspace_box_
protected

Definition at line 255 of file motion_planning_display.h.


The documentation for this class was generated from the following files:


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Thu Feb 27 2025 03:29:15