#include <motion_planning_display.h>
Definition at line 74 of file motion_planning_display.h.
Definition at line 76 of file motion_planning_display.cpp.
Definition at line 219 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::addStatusText | ( | const std::string & | text | ) |
Definition at line 722 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::addStatusText | ( | const std::vector< std::string > & | text | ) |
Definition at line 728 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::backgroundJobUpdate | ( | BackgroundProcessing::JobEvent | event | ) | [protected] |
Definition at line 313 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedDisplayPathCollisionEnabled | ( | ) | [private, slot] |
Definition at line 1083 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedDisplayPathVisualEnabled | ( | ) | [private, slot] |
Definition at line 1068 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedLoopDisplay | ( | ) | [private, slot] |
Definition at line 460 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedMetricsSetPayload | ( | ) | [private, slot] |
Definition at line 409 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedMetricsTextHeight | ( | ) | [private, slot] |
Definition at line 423 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedPlanningGroup | ( | ) | [private, slot] |
Definition at line 1029 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryCollidingLinkColor | ( | ) | [private, slot] |
Definition at line 902 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryGoalAlpha | ( | ) | [private, slot] |
Definition at line 896 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryGoalColor | ( | ) | [private, slot] |
Definition at line 884 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryGoalState | ( | ) | [private, slot] |
Definition at line 758 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryJointViolationColor | ( | ) | [private, slot] |
Definition at line 908 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryMarkerScale | ( | ) | [private, slot] |
Definition at line 872 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryStartAlpha | ( | ) | [private, slot] |
Definition at line 866 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryStartColor | ( | ) | [private, slot] |
Definition at line 854 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedQueryStartState | ( | ) | [private, slot] |
Definition at line 748 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedRobotPathAlpha | ( | ) | [private, slot] |
Definition at line 490 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedShowJointTorques | ( | ) | [private, slot] |
Definition at line 395 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedShowManipulability | ( | ) | [private, slot] |
Definition at line 381 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedShowManipulabilityIndex | ( | ) | [private, slot] |
Definition at line 367 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedShowTrail | ( | ) | [private, slot] |
Definition at line 465 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedShowWeightLimit | ( | ) | [private, slot] |
Definition at line 353 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedStateDisplayTime | ( | ) | [private, slot] |
Definition at line 1064 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedTrajectoryTopic | ( | ) | [private, slot] |
Definition at line 523 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changedWorkspace | ( | ) | [private, slot] |
Definition at line 1054 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::changePlanningGroup | ( | const std::string & | group | ) |
Definition at line 1014 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::clearTrajectoryTrail | ( | ) | [protected] |
Definition at line 453 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::computeMetrics | ( | bool | start, |
const std::string & | group, | ||
double | payload | ||
) | [protected] |
Definition at line 530 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::computeMetricsInternal | ( | std::map< std::string, double > & | metrics, |
const robot_interaction::RobotInteraction::EndEffector & | eef, | ||
const robot_state::RobotState & | state, | ||
double | payload | ||
) | [protected] |
Definition at line 545 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::displayMetrics | ( | bool | start | ) | [protected] |
Definition at line 603 of file motion_planning_display.cpp.
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 428 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::drawQueryGoalState | ( | ) | [protected] |
Definition at line 768 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::drawQueryStartState | ( | ) | [protected] |
Definition at line 660 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::executeMainLoopJobs | ( | ) | [protected] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
void moveit_rviz_plugin::MotionPlanningDisplay::fixedFrameChanged | ( | ) | [protected, virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1466 of file motion_planning_display.cpp.
std::string moveit_rviz_plugin::MotionPlanningDisplay::getCurrentPlanningGroup | ( | ) | const |
Definition at line 1059 of file motion_planning_display.cpp.
robot_state::RobotStateConstPtr moveit_rviz_plugin::MotionPlanningDisplay::getQueryGoalState | ( | ) | const [inline] |
Definition at line 95 of file motion_planning_display.h.
const robot_interaction::RobotInteraction::InteractionHandlerPtr& moveit_rviz_plugin::MotionPlanningDisplay::getQueryGoalStateHandler | ( | ) | const [inline] |
Definition at line 110 of file motion_planning_display.h.
robot_state::RobotStateConstPtr moveit_rviz_plugin::MotionPlanningDisplay::getQueryStartState | ( | ) | const [inline] |
Definition at line 90 of file motion_planning_display.h.
const robot_interaction::RobotInteraction::InteractionHandlerPtr& moveit_rviz_plugin::MotionPlanningDisplay::getQueryStartStateHandler | ( | ) | const [inline] |
Definition at line 105 of file motion_planning_display.h.
const robot_interaction::RobotInteractionPtr& moveit_rviz_plugin::MotionPlanningDisplay::getRobotInteraction | ( | ) | const [inline] |
Definition at line 100 of file motion_planning_display.h.
float moveit_rviz_plugin::MotionPlanningDisplay::getStateDisplayTime | ( | ) | [protected] |
Definition at line 1313 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::incomingDisplayTrajectory | ( | const moveit_msgs::DisplayTrajectory::ConstPtr & | msg | ) | [protected] |
ROS callback for an incoming path message.
Definition at line 1434 of file motion_planning_display.cpp.
bool moveit_rviz_plugin::MotionPlanningDisplay::isIKSolutionCollisionFree | ( | robot_state::JointStateGroup * | group, |
const std::vector< double > & | ik_solution | ||
) | const [protected] |
Definition at line 978 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::load | ( | const rviz::Config & | config | ) | [virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1399 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::onDisable | ( | ) | [protected, virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1294 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::onEnable | ( | ) | [protected, virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1265 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::onInitialize | ( | ) | [protected, virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 237 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::onRobotModelLoaded | ( | ) | [protected, virtual] |
This is an event called by loadRobotModel() in the MainLoop; do not call directly.
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1167 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::onSceneMonitorReceivedUpdate | ( | planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType | update_type | ) | [protected, virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1238 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::populateMenuHandler | ( | boost::shared_ptr< interactive_markers::MenuHandler > & | mh | ) | [protected] |
Definition at line 1134 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::publishInteractiveMarkers | ( | bool | pose_update | ) | [protected] |
Definition at line 829 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::recomputeQueryGoalStateMetrics | ( | ) | [protected] |
Definition at line 741 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::recomputeQueryStartStateMetrics | ( | ) | [protected] |
Definition at line 734 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::renderWorkspaceBox | ( | ) | [protected] |
Definition at line 497 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::reset | ( | void | ) | [virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 289 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::resetInteractiveMarkers | ( | ) | [private, slot] |
Definition at line 822 of file motion_planning_display.cpp.
Definition at line 711 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::save | ( | rviz::Config | config | ) | const [virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1421 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::scheduleDrawQueryGoalState | ( | robot_interaction::RobotInteraction::InteractionHandler * | handler, |
bool | error_state_changed | ||
) | [protected] |
Definition at line 925 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::scheduleDrawQueryStartState | ( | robot_interaction::RobotInteraction::InteractionHandler * | handler, |
bool | error_state_changed | ||
) | [protected] |
Definition at line 914 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::setQueryGoalState | ( | const robot_state::RobotState & | goal | ) |
Definition at line 956 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::setQueryStartState | ( | const robot_state::RobotState & | start | ) |
Definition at line 950 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::setQueryStateHelper | ( | bool | use_start_state, |
const std::string & | v | ||
) | [protected] |
Definition at line 1094 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::setStatusTextColor | ( | const QColor & | color | ) |
Definition at line 716 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::update | ( | float | wall_dt, |
float | ros_dt | ||
) | [virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1338 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::updateBackgroundJobProgressBar | ( | ) | [protected] |
Definition at line 318 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::updateInternal | ( | float | wall_dt, |
float | ros_dt | ||
) | [protected, virtual] |
Reimplemented from moveit_rviz_plugin::PlanningSceneDisplay.
Definition at line 1348 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::updateLinkColors | ( | ) | [protected] |
Definition at line 990 of file motion_planning_display.cpp.
Definition at line 943 of file motion_planning_display.cpp.
Definition at line 936 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::updateStateExceptModified | ( | robot_state::RobotState & | dest, |
const robot_state::RobotState & | src | ||
) | [protected] |
Definition at line 1220 of file motion_planning_display.cpp.
void moveit_rviz_plugin::MotionPlanningDisplay::useApproximateIK | ( | bool | flag | ) |
Definition at line 962 of file motion_planning_display.cpp.
bool moveit_rviz_plugin::MotionPlanningDisplay::animating_path_ [protected] |
Definition at line 228 of file motion_planning_display.h.
std::map<std::string, int> moveit_rviz_plugin::MotionPlanningDisplay::collision_links_goal_ [protected] |
Definition at line 246 of file motion_planning_display.h.
std::map<std::string, int> moveit_rviz_plugin::MotionPlanningDisplay::collision_links_start_ [protected] |
Definition at line 245 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::compute_weight_limit_property_ [protected] |
Definition at line 284 of file motion_planning_display.h.
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 252 of file motion_planning_display.h.
int moveit_rviz_plugin::MotionPlanningDisplay::current_state_ [protected] |
Definition at line 229 of file motion_planning_display.h.
float moveit_rviz_plugin::MotionPlanningDisplay::current_state_time_ [protected] |
Definition at line 230 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::display_path_collision_enabled_property_ [protected] |
Definition at line 278 of file motion_planning_display.h.
RobotStateVisualizationPtr moveit_rviz_plugin::MotionPlanningDisplay::display_path_robot_ [protected] |
Handles actually drawing the robot along motion plans.
Definition at line 217 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::display_path_visual_enabled_property_ [protected] |
Definition at line 277 of file motion_planning_display.h.
robot_trajectory::RobotTrajectoryPtr moveit_rviz_plugin::MotionPlanningDisplay::displaying_trajectory_message_ [protected] |
Definition at line 223 of file motion_planning_display.h.
std::map<std::string, dynamics_solver::DynamicsSolverPtr> moveit_rviz_plugin::MotionPlanningDisplay::dynamics_solver_ [protected] |
Definition at line 258 of file motion_planning_display.h.
Definition at line 236 of file motion_planning_display.h.
QDockWidget* moveit_rviz_plugin::MotionPlanningDisplay::frame_dock_ [protected] |
Definition at line 237 of file motion_planning_display.h.
Definition at line 292 of file motion_planning_display.h.
kinematics_metrics::KinematicsMetricsPtr moveit_rviz_plugin::MotionPlanningDisplay::kinematics_metrics_ [protected] |
Definition at line 257 of file motion_planning_display.h.
Definition at line 282 of file motion_planning_display.h.
boost::shared_ptr<interactive_markers::MenuHandler> moveit_rviz_plugin::MotionPlanningDisplay::menu_handler_goal_ [protected] |
Definition at line 244 of file motion_planning_display.h.
boost::shared_ptr<interactive_markers::MenuHandler> moveit_rviz_plugin::MotionPlanningDisplay::menu_handler_start_ [protected] |
Definition at line 243 of file motion_planning_display.h.
Definition at line 264 of file motion_planning_display.h.
rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::metrics_set_payload_property_ [protected] |
Definition at line 288 of file motion_planning_display.h.
rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::metrics_text_height_property_ [protected] |
Definition at line 289 of file motion_planning_display.h.
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 248 of file motion_planning_display.h.
Definition at line 262 of file motion_planning_display.h.
Definition at line 263 of file motion_planning_display.h.
rviz::EditableEnumProperty* moveit_rviz_plugin::MotionPlanningDisplay::planning_group_property_ [protected] |
Definition at line 266 of file motion_planning_display.h.
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 254 of file motion_planning_display.h.
Definition at line 227 of file motion_planning_display.h.
rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_colliding_link_color_property_ [protected] |
Definition at line 274 of file motion_planning_display.h.
rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_goal_alpha_property_ [protected] |
Definition at line 273 of file motion_planning_display.h.
rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_goal_color_property_ [protected] |
Definition at line 271 of file motion_planning_display.h.
robot_interaction::RobotInteraction::InteractionHandlerPtr moveit_rviz_plugin::MotionPlanningDisplay::query_goal_state_ [protected] |
Definition at line 242 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_goal_state_property_ [protected] |
Definition at line 268 of file motion_planning_display.h.
rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_marker_scale_property_ [protected] |
Definition at line 269 of file motion_planning_display.h.
rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_outside_joint_limits_link_color_property_ [protected] |
Definition at line 275 of file motion_planning_display.h.
Handles drawing the robot at the goal configuration.
Definition at line 216 of file motion_planning_display.h.
RobotStateVisualizationPtr moveit_rviz_plugin::MotionPlanningDisplay::query_robot_start_ [protected] |
Handles drawing the robot at the start configuration.
Definition at line 215 of file motion_planning_display.h.
rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_start_alpha_property_ [protected] |
Definition at line 272 of file motion_planning_display.h.
rviz::ColorProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_start_color_property_ [protected] |
Definition at line 270 of file motion_planning_display.h.
robot_interaction::RobotInteraction::InteractionHandlerPtr moveit_rviz_plugin::MotionPlanningDisplay::query_start_state_ [protected] |
Definition at line 241 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::query_start_state_property_ [protected] |
Definition at line 267 of file motion_planning_display.h.
robot_interaction::RobotInteractionPtr moveit_rviz_plugin::MotionPlanningDisplay::robot_interaction_ [protected] |
Definition at line 240 of file motion_planning_display.h.
rviz::FloatProperty* moveit_rviz_plugin::MotionPlanningDisplay::robot_path_alpha_property_ [protected] |
Definition at line 281 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::show_joint_torques_property_ [protected] |
Definition at line 287 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::show_manipulability_index_property_ [protected] |
Definition at line 285 of file motion_planning_display.h.
rviz::BoolProperty* moveit_rviz_plugin::MotionPlanningDisplay::show_manipulability_property_ [protected] |
Definition at line 286 of file motion_planning_display.h.
Definition at line 290 of file motion_planning_display.h.
rviz::EditableEnumProperty* moveit_rviz_plugin::MotionPlanningDisplay::state_display_time_property_ [protected] |
Definition at line 279 of file motion_planning_display.h.
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 220 of file motion_planning_display.h.
Ogre::SceneNode* moveit_rviz_plugin::MotionPlanningDisplay::text_display_scene_node_ [protected] |
displays texts
Definition at line 219 of file motion_planning_display.h.
Definition at line 221 of file motion_planning_display.h.
Definition at line 283 of file motion_planning_display.h.
robot_trajectory::RobotTrajectoryPtr moveit_rviz_plugin::MotionPlanningDisplay::trajectory_message_to_display_ [protected] |
Definition at line 224 of file motion_planning_display.h.
rviz::RosTopicProperty* moveit_rviz_plugin::MotionPlanningDisplay::trajectory_topic_property_ [protected] |
Definition at line 280 of file motion_planning_display.h.
Definition at line 226 of file motion_planning_display.h.
std::vector<rviz::Robot*> moveit_rviz_plugin::MotionPlanningDisplay::trajectory_trail_ [protected] |
Definition at line 225 of file motion_planning_display.h.
boost::mutex moveit_rviz_plugin::MotionPlanningDisplay::update_metrics_lock_ [protected] |
Definition at line 259 of file motion_planning_display.h.
boost::scoped_ptr<rviz::Shape> moveit_rviz_plugin::MotionPlanningDisplay::workspace_box_ [protected] |
Definition at line 233 of file motion_planning_display.h.