Go to the documentation of this file.
55 #include <std_msgs/String.h>
56 #include <moveit_msgs/DisplayTrajectory.h>
74 class RosTopicProperty;
94 void update(
float wall_dt,
float ros_dt)
override;
95 void reset()
override;
208 void displayTable(
const std::map<std::string, double>& values,
const Ogre::ColourValue& color,
209 const Ogre::Vector3& pos,
const Ogre::Quaternion& orient);
223 const double* ik_solution)
const;
225 void computeMetrics(
bool start,
const std::string& group,
double payload);
void onRobotModelLoaded() override
This is an event called by loadRobotModel() in the MainLoop; do not call directly.
~MotionPlanningDisplay() override
rviz::EnumProperty * planning_group_property_
rviz::BoolProperty * query_goal_state_property_
const moveit::core::RobotState & getPreviousState() const
void changedMetricsSetPayload()
void drawQueryStartState()
robot_interaction::InteractionHandlerPtr query_goal_state_
rviz::BoolProperty * compute_weight_limit_property_
void computeMetrics(bool start, const std::string &group, double payload)
const robot_interaction::RobotInteractionPtr & getRobotInteraction() const
std::shared_ptr< interactive_markers::MenuHandler > menu_handler_start_
void changedShowWeightLimit()
void rememberPreviousStartState()
void changedQueryCollidingLinkColor()
void setStatusTextColor(const QColor &color)
void scheduleDrawQueryStartState(robot_interaction::InteractionHandler *handler, bool error_state_changed)
ros::NodeHandle private_handle_
void setQueryStateHelper(bool use_start_state, const std::string &v)
void updateQueryGoalState()
void load(const rviz::Config &config) override
rviz::MovableText * text_to_display_
void publishInteractiveMarkers(bool pose_update)
ros::NodeHandle node_handle_
void changedShowJointTorques()
void save(rviz::Config config) const override
rviz::ColorProperty * query_colliding_link_color_property_
void scheduleDrawQueryGoalState(robot_interaction::InteractionHandler *handler, bool error_state_changed)
Ogre::SceneNode * text_display_scene_node_
displays texts
void changedPlanningGroup()
void changedMetricsTextHeight()
void renderWorkspaceBox()
void executeMainLoopJobs()
rviz::ColorProperty * query_outside_joint_limits_link_color_property_
rviz::FloatProperty * metrics_text_height_property_
std::map< std::string, LinkDisplayStatus > status_links_goal_
rviz::BoolProperty * show_workspace_property_
const robot_interaction::InteractionHandlerPtr & getQueryGoalStateHandler() const
void changedQueryStartAlpha()
std::unique_ptr< rviz::Shape > workspace_box_
void recomputeQueryGoalStateMetrics()
void updateQueryStartState()
rviz::Property * metrics_category_
rviz::BoolProperty * show_manipulability_property_
void update(float wall_dt, float ros_dt) override
void changePlanningGroup(const std::string &group)
void displayMetrics(bool start)
void drawQueryGoalState()
void updateQueryStates(const moveit::core::RobotState ¤t_state)
moveit::core::RobotStatePtr previous_state_
remember previous start state (updated before starting execution)
void changedShowManipulability()
void dropVisualizedTrajectory()
kinematics_metrics::KinematicsMetricsPtr kinematics_metrics_
std::map< std::string, bool > position_only_ik_
Some groups use position only ik, calls to the metrics have to be modified appropriately.
void resetInteractiveMarkers()
std::map< std::pair< bool, std::string >, std::map< std::string, double > > computed_metrics_
void changedQueryGoalState()
void changedAttachedBodyColor() override
bool isIKSolutionCollisionFree(moveit::core::RobotState *state, const moveit::core::JointModelGroup *group, const double *ik_solution) const
rviz::Property * plan_category_
TrajectoryVisualizationPtr trajectory_visual_
rviz::PanelDockWidget * frame_dock_
void toggleSelectPlanningGroupSubscription(bool enable)
void displayTable(const std::map< std::string, double > &values, const Ogre::ColourValue &color, const Ogre::Vector3 &pos, const Ogre::Quaternion &orient)
boost::mutex update_metrics_lock_
void onInitialize() override
void queryStartStateChanged()
void changedQueryGoalColor()
std::map< std::string, dynamics_solver::DynamicsSolverPtr > dynamics_solver_
void addStatusText(const std::string &text)
void resetStatusTextColor()
rviz::ColorProperty * query_start_color_property_
std::shared_ptr< interactive_markers::MenuHandler > menu_handler_goal_
void changedQueryGoalAlpha()
moveit::core::RobotStateConstPtr getQueryStartState() const
void fixedFrameChanged() override
rviz::Display * int_marker_display_
rviz::FloatProperty * query_goal_alpha_property_
rviz::BoolProperty * query_start_state_property_
void changedQueryStartColor()
rviz::ColorProperty * query_goal_color_property_
std::vector< std::shared_ptr< rviz::Shape > > place_locations_display_
void updateInternal(float wall_dt, float ros_dt) override
void updateStateExceptModified(moveit::core::RobotState &dest, const moveit::core::RobotState &src)
robot_interaction::InteractionHandlerPtr query_start_state_
void updateBackgroundJobProgressBar()
std::set< std::string > modified_groups_
void clearRobotModel() override
void backgroundJobUpdate(moveit::tools::BackgroundProcessing::JobEvent event, const std::string &jobname)
void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type) override
void setQueryStartState(const moveit::core::RobotState &start)
std::map< std::string, LinkDisplayStatus > status_links_start_
void changedQueryStartState()
void visualizePlaceLocations(const std::vector< geometry_msgs::PoseStamped > &place_poses)
MotionPlanningFrame * frame_
void computeMetricsInternal(std::map< std::string, double > &metrics, const robot_interaction::EndEffectorInteraction &eef, const moveit::core::RobotState &state, double payload)
void useApproximateIK(bool flag)
rviz::Property * path_category_
void changedShowManipulabilityIndex()
rviz::BoolProperty * show_manipulability_index_property_
std::string getCurrentPlanningGroup() const
void queryGoalStateChanged()
rviz::BoolProperty * show_joint_torques_property_
rviz::FloatProperty * query_start_alpha_property_
void onNewPlanningSceneState() override
This is called upon successful retrieval of the (initial) planning scene state.
void changedQueryJointViolationColor()
const robot_interaction::InteractionHandlerPtr & getQueryStartStateHandler() const
void clearPlaceLocationsDisplay()
void selectPlanningGroupCallback(const std_msgs::StringConstPtr &msg)
robot_interaction::RobotInteractionPtr robot_interaction_
void populateMenuHandler(std::shared_ptr< interactive_markers::MenuHandler > &mh)
rviz::FloatProperty * query_marker_scale_property_
void setQueryGoalState(const moveit::core::RobotState &goal)
void changedQueryMarkerScale()
void setName(const QString &name) override
void motionPanelVisibilityChange(bool enable)
bool text_display_for_start_
indicates whether the text display is for the start state or not
RobotStateVisualizationPtr query_robot_goal_
Handles drawing the robot at the goal configuration.
rviz::FloatProperty * metrics_set_payload_property_
RobotStateVisualizationPtr query_robot_start_
Handles drawing the robot at the start configuration.
void recomputeQueryStartStateMetrics()
void onDisable() override
moveit::core::RobotStateConstPtr getQueryGoalState() const
ros::Subscriber planning_group_sub_
visualization
Author(s): Ioan Sucan
, Dave Coleman , Sachin Chitta
autogenerated on Sat Mar 15 2025 02:27:25