moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <motion_planning_display.h>
Signals | |
void | queryStartStateChanged () |
void | queryGoalStateChanged () |
Public Member Functions | |
MotionPlanningDisplay () | |
~MotionPlanningDisplay () override | |
void | load (const rviz_common::Config &config) override |
void | save (rviz_common::Config config) const override |
void | update (float wall_dt, float ros_dt) override |
void | reset () override |
moveit::core::RobotStateConstPtr | getQueryStartState () const |
moveit::core::RobotStateConstPtr | getQueryGoalState () const |
const moveit::core::RobotState & | getPreviousState () const |
const robot_interaction::RobotInteractionPtr & | getRobotInteraction () const |
const robot_interaction::InteractionHandlerPtr & | getQueryStartStateHandler () const |
const robot_interaction::InteractionHandlerPtr & | getQueryGoalStateHandler () const |
void | dropVisualizedTrajectory () |
void | setQueryStartState (const moveit::core::RobotState &start) |
void | setQueryGoalState (const moveit::core::RobotState &goal) |
void | updateQueryStates (const moveit::core::RobotState ¤t_state) |
void | updateQueryStartState () |
void | updateQueryGoalState () |
void | rememberPreviousStartState () |
void | useApproximateIK (bool flag) |
void | clearPlaceLocationsDisplay () |
void | visualizePlaceLocations (const std::vector< geometry_msgs::msg::PoseStamped > &place_poses) |
std::string | getCurrentPlanningGroup () const |
void | changePlanningGroup (const std::string &group) |
void | addStatusText (const std::string &text) |
void | addStatusText (const std::vector< std::string > &text) |
void | setStatusTextColor (const QColor &color) |
void | resetStatusTextColor () |
void | toggleSelectPlanningGroupSubscription (bool enable) |
![]() | |
PlanningSceneDisplay (bool listen_to_planning_scene=true, bool show_scene_robot=true) | |
~PlanningSceneDisplay () override | |
void | load (const rviz_common::Config &config) override |
void | save (rviz_common::Config config) const override |
void | update (float wall_dt, float ros_dt) override |
void | reset () override |
void | setLinkColor (const std::string &link_name, const QColor &color) |
void | unsetLinkColor (const std::string &link_name) |
void | queueRenderSceneGeometry () |
void | addBackgroundJob (const std::function< void()> &job, const std::string &name) |
void | spawnBackgroundJob (const std::function< void()> &job) |
void | addMainLoopJob (const std::function< void()> &job) |
queue the execution of this function for the next time the main update() loop gets called More... | |
void | waitForAllMainLoopJobs () |
void | clearJobs () |
remove all queued jobs More... | |
const std::string | getMoveGroupNS () const |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
bool | waitForCurrentRobotState (const rclcpp::Time &t) |
wait for robot state more recent than t More... | |
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 planning_scene_monitor::PlanningSceneMonitorPtr & | getPlanningSceneMonitor () |
Public Attributes | |
std::vector< std::shared_ptr< rviz_rendering::Shape > > | place_locations_display_ |
Protected Types | |
enum | LinkDisplayStatus { COLLISION_LINK , OUTSIDE_BOUNDS_LINK } |
Protected Member Functions | |
void | clearRobotModel () override |
void | onRobotModelLoaded () override |
This is an event called by loadRobotModel() in the MainLoop; do not call directly. More... | |
void | onNewPlanningSceneState () override |
This is called upon successful retrieval of the (initial) planning scene state. More... | |
void | onSceneMonitorReceivedUpdate (planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type) override |
void | updateInternal (float wall_dt, float ros_dt) override |
void | renderWorkspaceBox () |
void | updateLinkColors () |
void | displayTable (const std::map< std::string, double > &values, const Ogre::ColourValue &color, const Ogre::Vector3 &pos, const Ogre::Quaternion &orient) |
void | displayMetrics (bool start) |
void | executeMainLoopJobs () |
void | publishInteractiveMarkers (bool pose_update) |
void | recomputeQueryStartStateMetrics () |
void | recomputeQueryGoalStateMetrics () |
void | drawQueryStartState () |
void | drawQueryGoalState () |
void | scheduleDrawQueryStartState (robot_interaction::InteractionHandler *handler, bool error_state_changed) |
void | scheduleDrawQueryGoalState (robot_interaction::InteractionHandler *handler, bool error_state_changed) |
bool | isIKSolutionCollisionFree (moveit::core::RobotState *state, const moveit::core::JointModelGroup *group, const double *ik_solution) const |
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 | updateStateExceptModified (moveit::core::RobotState &dest, const moveit::core::RobotState &src) |
void | updateBackgroundJobProgressBar () |
void | backgroundJobUpdate (moveit::tools::BackgroundProcessing::JobEvent event, const std::string &jobname) |
void | setQueryStateHelper (bool use_start_state, const std::string &v) |
void | populateMenuHandler (std::shared_ptr< interactive_markers::MenuHandler > &mh) |
void | selectPlanningGroupCallback (const std_msgs::msg::String::ConstSharedPtr &msg) |
void | onInitialize () override |
void | onEnable () override |
void | onDisable () override |
void | fixedFrameChanged () override |
![]() | |
void | loadRobotModel () |
virtual planning_scene_monitor::PlanningSceneMonitorPtr | createPlanningSceneMonitor () |
void | calculateOffsetPosition () |
Set the scene node's position, given the target frame and the planning frame. More... | |
void | executeMainLoopJobs () |
void | sceneMonitorReceivedUpdate (planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type) |
void | renderPlanningScene () |
void | setLinkColor (rviz_default_plugins::robot::Robot *robot, const std::string &link_name, const QColor &color) |
void | unsetLinkColor (rviz_default_plugins::robot::Robot *robot, const std::string &link_name) |
void | setGroupColor (rviz_default_plugins::robot::Robot *robot, const std::string &group_name, const QColor &color) |
void | unsetGroupColor (rviz_default_plugins::robot::Robot *robot, const std::string &group_name) |
void | unsetAllColors (rviz_default_plugins::robot::Robot *robot) |
void | onInitialize () override |
void | onEnable () override |
void | onDisable () override |
void | fixedFrameChanged () override |
Protected Attributes | |
RobotStateVisualizationPtr | query_robot_start_ |
Handles drawing the robot at the start configuration. More... | |
RobotStateVisualizationPtr | query_robot_goal_ |
Handles drawing the robot at the goal configuration. More... | |
Ogre::SceneNode * | text_display_scene_node_ |
displays texts More... | |
bool | text_display_for_start_ |
indicates whether the text display is for the start state or not More... | |
rviz_rendering::MovableText * | text_to_display_ |
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr | planning_group_sub_ |
std::unique_ptr< rviz_rendering::Shape > | workspace_box_ |
MotionPlanningFrame * | frame_ |
rviz_common::PanelDockWidget * | frame_dock_ |
robot_interaction::RobotInteractionPtr | robot_interaction_ |
robot_interaction::InteractionHandlerPtr | query_start_state_ |
robot_interaction::InteractionHandlerPtr | query_goal_state_ |
std::shared_ptr< interactive_markers::MenuHandler > | menu_handler_start_ |
std::shared_ptr< interactive_markers::MenuHandler > | menu_handler_goal_ |
std::map< std::string, LinkDisplayStatus > | status_links_start_ |
std::map< std::string, LinkDisplayStatus > | status_links_goal_ |
moveit::core::RobotStatePtr | previous_state_ |
remember previous start state (updated before starting execution) More... | |
std::set< std::string > | modified_groups_ |
std::map< std::pair< bool, std::string >, std::map< std::string, double > > | computed_metrics_ |
std::map< std::string, bool > | position_only_ik_ |
Some groups use position only ik, calls to the metrics have to be modified appropriately. More... | |
kinematics_metrics::KinematicsMetricsPtr | kinematics_metrics_ |
std::map< std::string, dynamics_solver::DynamicsSolverPtr > | dynamics_solver_ |
std::mutex | update_metrics_lock_ |
TrajectoryVisualizationPtr | trajectory_visual_ |
rviz_common::properties::Property * | path_category_ |
rviz_common::properties::Property * | plan_category_ |
rviz_common::properties::Property * | metrics_category_ |
rviz_common::properties::EditableEnumProperty * | planning_group_property_ |
rviz_common::properties::BoolProperty * | query_start_state_property_ |
rviz_common::properties::BoolProperty * | query_goal_state_property_ |
rviz_common::properties::FloatProperty * | query_marker_scale_property_ |
rviz_common::properties::ColorProperty * | query_start_color_property_ |
rviz_common::properties::ColorProperty * | query_goal_color_property_ |
rviz_common::properties::FloatProperty * | query_start_alpha_property_ |
rviz_common::properties::FloatProperty * | query_goal_alpha_property_ |
rviz_common::properties::ColorProperty * | query_colliding_link_color_property_ |
rviz_common::properties::ColorProperty * | query_outside_joint_limits_link_color_property_ |
rviz_common::properties::BoolProperty * | compute_weight_limit_property_ |
rviz_common::properties::BoolProperty * | show_manipulability_index_property_ |
rviz_common::properties::BoolProperty * | show_manipulability_property_ |
rviz_common::properties::BoolProperty * | show_joint_torques_property_ |
rviz_common::properties::FloatProperty * | metrics_set_payload_property_ |
rviz_common::properties::FloatProperty * | metrics_text_height_property_ |
rviz_common::properties::BoolProperty * | show_workspace_property_ |
rviz_common::Display * | int_marker_display_ |
![]() | |
planning_scene_monitor::PlanningSceneMonitorPtr | planning_scene_monitor_ |
std::mutex | robot_model_loading_lock_ |
moveit::tools::BackgroundProcessing | background_process_ |
std::deque< std::function< void()> > | main_loop_jobs_ |
std::mutex | main_loop_jobs_lock_ |
std::condition_variable | main_loop_jobs_empty_condition_ |
Ogre::SceneNode * | planning_scene_node_ |
displays planning scene with everything in it More... | |
RobotStateVisualizationPtr | planning_scene_robot_ |
PlanningSceneRenderPtr | planning_scene_render_ |
bool | planning_scene_needs_render_ |
bool | robot_state_needs_render_ |
float | current_scene_time_ |
rviz_common::properties::Property * | scene_category_ |
rviz_common::properties::Property * | robot_category_ |
rviz_common::properties::StringProperty * | move_group_ns_property_ |
rviz_common::properties::StringProperty * | robot_description_property_ |
rviz_common::properties::StringProperty * | scene_name_property_ |
rviz_common::properties::BoolProperty * | scene_enabled_property_ |
rviz_common::properties::BoolProperty * | scene_robot_visual_enabled_property_ |
rviz_common::properties::BoolProperty * | scene_robot_collision_enabled_property_ |
rviz_common::properties::RosTopicProperty * | planning_scene_topic_property_ |
rviz_common::properties::FloatProperty * | robot_alpha_property_ |
rviz_common::properties::FloatProperty * | scene_alpha_property_ |
rviz_common::properties::ColorProperty * | scene_color_property_ |
rviz_common::properties::ColorProperty * | attached_body_color_property_ |
rviz_common::properties::FloatProperty * | scene_display_time_property_ |
rviz_common::properties::EnumProperty * | octree_render_property_ |
rviz_common::properties::EnumProperty * | octree_coloring_property_ |
rclcpp::Node::SharedPtr | node_ |
Additional Inherited Members | |
![]() | |
virtual void | changedAttachedBodyColor () |
Definition at line 97 of file motion_planning_display.h.
|
protected |
Enumerator | |
---|---|
COLLISION_LINK | |
OUTSIDE_BOUNDS_LINK |
Definition at line 206 of file motion_planning_display.h.
moveit_rviz_plugin::MotionPlanningDisplay::MotionPlanningDisplay | ( | ) |
Definition at line 86 of file motion_planning_display.cpp.
|
override |
Definition at line 195 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::addStatusText | ( | const std::string & | text | ) |
Definition at line 686 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::addStatusText | ( | const std::vector< std::string > & | text | ) |
Definition at line 692 of file motion_planning_display.cpp.
|
protected |
Definition at line 326 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changePlanningGroup | ( | const std::string & | group | ) |
Definition at line 1009 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::clearPlaceLocationsDisplay | ( | ) |
Definition at line 1434 of file motion_planning_display.cpp.
|
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 1123 of file motion_planning_display.cpp.
|
protected |
Definition at line 480 of file motion_planning_display.cpp.
|
protected |
Definition at line 495 of file motion_planning_display.cpp.
|
protected |
Definition at line 555 of file motion_planning_display.cpp.
|
protected |
Definition at line 434 of file motion_planning_display.cpp.
|
protected |
Definition at line 732 of file motion_planning_display.cpp.
|
protected |
Definition at line 612 of file motion_planning_display.cpp.
|
inline |
Definition at line 142 of file motion_planning_display.h.
|
protected |
|
overrideprotected |
Definition at line 1421 of file motion_planning_display.cpp.
std::string moveit_rviz_plugin::MotionPlanningDisplay::getCurrentPlanningGroup | ( | ) | const |
Definition at line 1051 of file motion_planning_display.cpp.
|
inline |
Definition at line 122 of file motion_planning_display.h.
|
inline |
Definition at line 117 of file motion_planning_display.h.
|
inline |
Definition at line 137 of file motion_planning_display.h.
|
inline |
Definition at line 112 of file motion_planning_display.h.
|
inline |
Definition at line 132 of file motion_planning_display.h.
|
inline |
Definition at line 127 of file motion_planning_display.h.
|
protected |
Definition at line 966 of file motion_planning_display.cpp.
|
override |
Definition at line 1328 of file motion_planning_display.cpp.
|
overrideprotected |
Definition at line 1287 of file motion_planning_display.cpp.
|
overrideprotected |
Definition at line 1266 of file motion_planning_display.cpp.
|
overrideprotected |
Definition at line 208 of file motion_planning_display.cpp.
|
overrideprotectedvirtual |
This is called upon successful retrieval of the (initial) planning scene state.
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1211 of file motion_planning_display.cpp.
|
overrideprotectedvirtual |
This is an event called by loadRobotModel() in the MainLoop; do not call directly.
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1140 of file motion_planning_display.cpp.
|
overrideprotectedvirtual |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1254 of file motion_planning_display.cpp.
|
protected |
Definition at line 1091 of file motion_planning_display.cpp.
|
protected |
Definition at line 804 of file motion_planning_display.cpp.
|
signal |
|
signal |
|
protected |
Definition at line 705 of file motion_planning_display.cpp.
|
protected |
Definition at line 698 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::rememberPreviousStartState | ( | ) |
Definition at line 937 of file motion_planning_display.cpp.
|
protected |
Definition at line 457 of file motion_planning_display.cpp.
|
override |
Definition at line 304 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::resetStatusTextColor | ( | ) |
Definition at line 675 of file motion_planning_display.cpp.
|
override |
Definition at line 1391 of file motion_planning_display.cpp.
|
protected |
Definition at line 911 of file motion_planning_display.cpp.
|
protected |
Definition at line 901 of file motion_planning_display.cpp.
|
protected |
Definition at line 298 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::setQueryGoalState | ( | const moveit::core::RobotState & | goal | ) |
Definition at line 948 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::setQueryStartState | ( | const moveit::core::RobotState & | start | ) |
Definition at line 942 of file motion_planning_display.cpp.
|
protected |
Definition at line 1056 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::setStatusTextColor | ( | const QColor & | color | ) |
Definition at line 680 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::toggleSelectPlanningGroupSubscription | ( | bool | enable | ) |
Definition at line 284 of file motion_planning_display.cpp.
|
override |
Definition at line 1308 of file motion_planning_display.cpp.
|
protected |
Definition at line 332 of file motion_planning_display.cpp.
|
overrideprotectedvirtual |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1318 of file motion_planning_display.cpp.
|
protected |
Definition at line 981 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::updateQueryGoalState | ( | ) |
Definition at line 929 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::updateQueryStartState | ( | ) |
Definition at line 921 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::updateQueryStates | ( | const moveit::core::RobotState & | current_state | ) |
Definition at line 1235 of file motion_planning_display.cpp.
|
protected |
Definition at line 1216 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::useApproximateIK | ( | bool | flag | ) |
Definition at line 954 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::visualizePlaceLocations | ( | const std::vector< geometry_msgs::msg::PoseStamped > & | place_poses | ) |
Definition at line 1441 of file motion_planning_display.cpp.
|
protected |
Definition at line 318 of file motion_planning_display.h.
|
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 290 of file motion_planning_display.h.
|
protected |
Definition at line 296 of file motion_planning_display.h.
|
protected |
Definition at line 270 of file motion_planning_display.h.
|
protected |
Definition at line 271 of file motion_planning_display.h.
|
protected |
Definition at line 326 of file motion_planning_display.h.
|
protected |
Definition at line 295 of file motion_planning_display.h.
|
protected |
Definition at line 278 of file motion_planning_display.h.
|
protected |
Definition at line 277 of file motion_planning_display.h.
|
protected |
Definition at line 305 of file motion_planning_display.h.
|
protected |
Definition at line 322 of file motion_planning_display.h.
|
protected |
Definition at line 323 of file motion_planning_display.h.
|
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 286 of file motion_planning_display.h.
|
protected |
Definition at line 303 of file motion_planning_display.h.
std::vector<std::shared_ptr<rviz_rendering::Shape> > moveit_rviz_plugin::MotionPlanningDisplay::place_locations_display_ |
Definition at line 160 of file motion_planning_display.h.
|
protected |
Definition at line 304 of file motion_planning_display.h.
|
protected |
Definition at line 307 of file motion_planning_display.h.
|
protected |
Definition at line 264 of file motion_planning_display.h.
|
protected |
Some groups use position only ik, calls to the metrics have to be modified appropriately.
Definition at line 292 of file motion_planning_display.h.
|
protected |
remember previous start state (updated before starting execution)
Definition at line 282 of file motion_planning_display.h.
|
protected |
Definition at line 315 of file motion_planning_display.h.
|
protected |
Definition at line 314 of file motion_planning_display.h.
|
protected |
Definition at line 312 of file motion_planning_display.h.
|
protected |
Definition at line 276 of file motion_planning_display.h.
|
protected |
Definition at line 309 of file motion_planning_display.h.
|
protected |
Definition at line 310 of file motion_planning_display.h.
|
protected |
Definition at line 316 of file motion_planning_display.h.
|
protected |
Handles drawing the robot at the goal configuration.
Definition at line 258 of file motion_planning_display.h.
|
protected |
Handles drawing the robot at the start configuration.
Definition at line 257 of file motion_planning_display.h.
|
protected |
Definition at line 313 of file motion_planning_display.h.
|
protected |
Definition at line 311 of file motion_planning_display.h.
|
protected |
Definition at line 275 of file motion_planning_display.h.
|
protected |
Definition at line 308 of file motion_planning_display.h.
|
protected |
Definition at line 274 of file motion_planning_display.h.
|
protected |
Definition at line 321 of file motion_planning_display.h.
|
protected |
Definition at line 319 of file motion_planning_display.h.
|
protected |
Definition at line 320 of file motion_planning_display.h.
|
protected |
Definition at line 324 of file motion_planning_display.h.
|
protected |
Definition at line 280 of file motion_planning_display.h.
|
protected |
Definition at line 279 of file motion_planning_display.h.
|
protected |
indicates whether the text display is for the start state or not
Definition at line 261 of file motion_planning_display.h.
|
protected |
displays texts
Definition at line 260 of file motion_planning_display.h.
|
protected |
Definition at line 262 of file motion_planning_display.h.
|
protected |
Definition at line 300 of file motion_planning_display.h.
|
protected |
Definition at line 297 of file motion_planning_display.h.
|
protected |
Definition at line 267 of file motion_planning_display.h.