Convenience class wrapping a motion plan request and its meta-data. More...
#include <move_arm_utils.h>
| Public Member Functions | |
| void | addTrajectoryId (unsigned int id) | 
| bool | areCollisionsVisible () const | 
| Return whether or not the small red spheres corresponding to collision points are being published. | |
| bool | areJointControlsVisible () const | 
| returns whether the interactive joint control markers are visible. | |
| visualization_msgs::MarkerArray & | getCollisionMarkers () | 
| Each motion plan request stores an array of small red spheres corresponding to collision points. | |
| bool | getConstrainPitch () const | 
| bool | getConstrainRoll () const | 
| bool | getConstrainYaw () const | 
| std::string | getEndEffectorLink () const | 
| Returns the name of the link that IK is performed for. | |
| const std_msgs::ColorRGBA & | getGoalColor () const | 
| Returns the color of the markers of the goal position. | |
| planning_models::KinematicState * | getGoalState () | 
| Returns a KinematicState pointer corresponding to the goal joint constraints of the robot. | |
| std::string | getGroupName () const | 
| Returns the name of the planning group associated with the motion plan request (usually, right or left arm) | |
| unsigned int | getId () const | 
| std::vector< std::string > | getJointNamesInGoal () | 
| Returns a vector of joint messages corresponding to all the joints in the goal constraints of the underlying motion plan request message. | |
| tf::Transform | getLastGoodGoalPose () const | 
| Returns the last goal pose that had a good IK solution. | |
| tf::Transform | getLastGoodStartPose () const | 
| Returns the last starting pose that had a good IK solution. | |
| arm_navigation_msgs::MotionPlanRequest & | getMotionPlanRequest () | 
| Gets the underlying motion plan request message. | |
| const std::string & | getName () const | 
| Returns the unique Id of the motion plan request. | |
| unsigned int | getNextTrajectoryId () const | 
| double | getPitchTolerance () const | 
| unsigned int | getPlanningSceneId () const | 
| std::string | getPlanningSceneName () const | 
| Returns the unique planning scene Id that this motion plan request is associated with. | |
| RenderType | getRenderType () const | 
| Gets what mesh to display in RVIZ. | |
| double | getRollTolerance () const | 
| const std::string & | getSource () const | 
| Returns the pipeline stage associated with this motion plan request. | |
| const std_msgs::ColorRGBA & | getStartColor () const | 
| Returns the color of the markers of the start position. | |
| planning_models::KinematicState * | getStartState () | 
| Returns a KinematicState pointer corresponding to the starting joint state of the robot. | |
| std::set< unsigned int > & | getTrajectories () | 
| Returns a vector of unique trajectory Ids associated with this motion plan request. | |
| double | getYawTolerance () const | 
| bool | hasGoodIKSolution (const PositionType &type) const | 
| Returns true if an IK solution was found for this request, and false otherwise. | |
| bool | hasPathConstraints () const | 
| bool | hasRefreshedColors () const | 
| Returns true if the refresh counter has been exhausted, and false otherwise. | |
| bool | hasStateChanged () const | 
| Returns true if the joint values or the color of the motion plan request has changed. | |
| bool | hasTrajectoryId (unsigned int id) const | 
| void | hide () | 
| Sets both the start and end positions to invisible. | |
| void | hideCollisions () | 
| Convenience shorthand for setCollisionsVisible(false) | |
| void | hideGoal () | 
| Shorthand for setEndVisible(false) | |
| void | hideStart () | 
| Shorthand for setStartVisible(false) | |
| bool | isEndVisible () const | 
| Returns true if the goal kinematic state of the robot is being published as a set of markers or false otherwise. | |
| bool | isGoalEditable () const | 
| If true, then a 6DOF control and joint controls will be visible for the goal position of the robot. If false, these controls will not be shown. | |
| bool | isJointNameInGoal (std::string joint) | 
| returns whether or not the specified joint name is part of the goal constraints of the motion plan request. | |
| bool | isStartEditable () const | 
| If true, then a 6DOF control and joint controls will be visible for the start position of the robot. If false, these controls will not be shown. | |
| bool | isStartVisible () const | 
| Returns true if the starting kinematic state of the robot is being published as a set of markers or false otherwise. | |
| MotionPlanRequestData () | |
| MotionPlanRequestData (const planning_models::KinematicState *robot_state) | |
| MotionPlanRequestData (const unsigned int &id, const std::string &source, const arm_navigation_msgs::MotionPlanRequest &request, const planning_models::KinematicState *robot_state, const std::string &end_effector_link) | |
| void | refreshColors () | 
| Tell the planning scene editor to stop publishing markers for a while so that the colors of the motion plan request can be changed. | |
| void | removeTrajectoryId (unsigned int id) | 
| void | reset () | 
| Deletes the kinematic states associated with the motion plan request. | |
| void | setCollisionsVisible (bool visible) | 
| Either show or hide the red spheres corresponding to collision points. | |
| void | setConstrainPitch (bool s) | 
| void | setConstrainRoll (bool s) | 
| void | setConstrainYaw (bool s) | 
| void | setEndEffectorLink (const std::string &name) | 
| Sets the name of the link that IK is performed for. | |
| void | setEndVisible (bool visible) | 
| see isEndVisible | |
| void | setGoalAndPathPositionOrientationConstraints (arm_navigation_msgs::MotionPlanRequest &mpr, planning_scene_utils::PositionType type) const | 
| void | setGoalColor (std_msgs::ColorRGBA color) | 
| Sets the color of the markers for the goal position. | |
| void | setGoalEditable (bool editable) | 
| If true, then a 6DOF control and joint controls will be visible for the goal position of the robot. If false, these controls will not be shown. | |
| void | setGoalState (planning_models::KinematicState *state) | 
| Sets the kinematic state corresponding to the goal joint state of the robot. | |
| void | setGoalStateValues (std::map< std::string, double > &joint_values) | 
| Sets the goal state joint values of the robot. | |
| void | setGroupName (const std::string &name) | 
| Sets the name of the planning group associated with the motion plan request (usually, right or left arm) | |
| void | setHasGoodIKSolution (const bool &solution, const PositionType &type) | 
| Set whether or not an IK solution was found for the start or end of this request. | |
| void | setHasRefreshedColors (bool refresh) | 
| See hasRefreshedColors. | |
| void | setId (const unsigned int id) | 
| Sets the unique Id of the motion plan request. | |
| void | setJointControlsVisible (bool visible, PlanningSceneEditor *editor) | 
| Either creates or destroys the interactive joint control markers for this request. | |
| void | setLastGoodGoalPose (tf::Transform pose) | 
| Stores a poase as the last goal pose with a good IK solution. | |
| void | setLastGoodStartPose (tf::Transform pose) | 
| Stores a pose as the last starting pose with a good IK solution. | |
| void | setMotionPlanRequest (const arm_navigation_msgs::MotionPlanRequest &request) | 
| Sets the underlying motion plan request message. | |
| void | setPathConstraints (bool has) | 
| void | setPitchTolerance (double s) | 
| void | setPlanningSceneId (const unsigned int id) | 
| Sets the planning scene Id that this motion plan request is associated with. | |
| void | setRenderType (RenderType renderType) | 
| Sets what mesh to display in RVIZ. | |
| void | setRollTolerance (double s) | 
| void | setSource (const std::string &source) | 
| Set the pipeline stage associated with this motion plan request. | |
| void | setStartColor (std_msgs::ColorRGBA color) | 
| Sets the color of the markers for the start position. | |
| void | setStartEditable (bool editable) | 
| If true, then a 6DOF control and joint controls will be visible for the start position of the robot. If false, these controls will not be shown. | |
| void | setStartState (planning_models::KinematicState *state) | 
| Sets the kinematic state corresponding to the starting joint state of the robot. | |
| void | setStartStateValues (std::map< std::string, double > &joint_values) | 
| Sets the start state joint values of the robot. | |
| void | setStartVisible (bool visible) | 
| see isStartVisible | |
| void | setStateChanged (bool changed) | 
| Set the flag recording whether or not the joint state or color of the motion plan request has changed. | |
| void | setYawTolerance (double s) | 
| bool | shouldRefreshColors () const | 
| Returns true if the motion plan request's colors have changed, and false otherwise. | |
| void | show () | 
| Sets both the start and end positions to be published. | |
| void | showCollisions () | 
| Convenience shorthand for setCollisionsVisible(true) | |
| void | showGoal () | 
| Shorthand for setEndVisible(true) | |
| void | showStart () | 
| Shorthand for setStartVisible(true) | |
| void | updateCollisionMarkers (planning_environment::CollisionModels *cm_, ros::ServiceClient *distance_state_validity_service_client_) | 
| Fills the member marker array with small red spheres associated with collision points. | |
| void | updateGoalState () | 
| Updates the KinematicState pointer goal_state_ to reflect changes to the underlying motion plan request message. | |
| void | updateStartState () | 
| Updates the KinematicState pointer start_state_ to reflect changes to the underlying motion plan request message. | |
| Public Attributes | |
| ros::Duration | refresh_timer_ | 
| If the color of the motion plan request changes, this counter is incremented until it reaches a value specified by the planning scene editor. This is done to allow the display markers time to disappear before their colors are changed. | |
| Protected Attributes | |
| bool | are_collisions_visible_ | 
| bool | are_joint_controls_visible_ | 
| visualization_msgs::MarkerArray | collision_markers_ | 
| bool | constrain_pitch_ | 
| bool | constrain_roll_ | 
| bool | constrain_yaw_ | 
| std::string | end_effector_link_ | 
| std_msgs::ColorRGBA | goal_color_ | 
| planning_models::KinematicState * | goal_state_ | 
| std::string | group_name_ | 
| bool | has_good_goal_ik_solution_ | 
| bool | has_good_start_ik_solution_ | 
| bool | has_path_constraints_ | 
| bool | has_refreshed_colors_ | 
| bool | has_state_changed_ | 
| unsigned int | id_ | 
| bool | is_goal_editable_ | 
| bool | is_goal_visible_ | 
| bool | is_start_editable_ | 
| bool | is_start_visible_ | 
| tf::Transform | last_good_goal_pose_ | 
| tf::Transform | last_good_start_pose_ | 
| arm_navigation_msgs::MotionPlanRequest | motion_plan_request_ | 
| std::string | name_ | 
| unsigned int | next_trajectory_id_ | 
| double | pitch_tolerance_ | 
| unsigned int | planning_scene_id_ | 
| RenderType | render_type_ | 
| double | roll_tolerance_ | 
| bool | should_refresh_colors_ | 
| std::string | source_ | 
| std_msgs::ColorRGBA | start_color_ | 
| planning_models::KinematicState * | start_state_ | 
| std::set< unsigned int > | trajectories_ | 
| double | yaw_tolerance_ | 
Convenience class wrapping a motion plan request and its meta-data.
Class MotionPlanRequestData
Definition at line 333 of file move_arm_utils.h.
Definition at line 376 of file move_arm_utils.h.
| MotionPlanRequestData::MotionPlanRequestData | ( | const planning_models::KinematicState * | robot_state | ) | 
Definition at line 309 of file move_arm_utils.cpp.
| planning_scene_utils::MotionPlanRequestData::MotionPlanRequestData | ( | const unsigned int & | id, | 
| const std::string & | source, | ||
| const arm_navigation_msgs::MotionPlanRequest & | request, | ||
| const planning_models::KinematicState * | robot_state, | ||
| const std::string & | end_effector_link | ||
| ) | 
| void planning_scene_utils::MotionPlanRequestData::addTrajectoryId | ( | unsigned int | id | ) |  [inline] | 
Definition at line 817 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::areCollisionsVisible | ( | ) | const  [inline] | 
Return whether or not the small red spheres corresponding to collision points are being published.
Definition at line 463 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::areJointControlsVisible | ( | ) | const  [inline] | 
returns whether the interactive joint control markers are visible.
Definition at line 434 of file move_arm_utils.h.
| visualization_msgs::MarkerArray& planning_scene_utils::MotionPlanRequestData::getCollisionMarkers | ( | ) |  [inline] | 
Each motion plan request stores an array of small red spheres corresponding to collision points.
Definition at line 457 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::getConstrainPitch | ( | ) | const  [inline] | 
Definition at line 845 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::getConstrainRoll | ( | ) | const  [inline] | 
Definition at line 837 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::getConstrainYaw | ( | ) | const  [inline] | 
Definition at line 853 of file move_arm_utils.h.
| std::string planning_scene_utils::MotionPlanRequestData::getEndEffectorLink | ( | ) | const  [inline] | 
Returns the name of the link that IK is performed for.
Definition at line 580 of file move_arm_utils.h.
| const std_msgs::ColorRGBA& planning_scene_utils::MotionPlanRequestData::getGoalColor | ( | ) | const  [inline] | 
Returns the color of the markers of the goal position.
Definition at line 718 of file move_arm_utils.h.
| planning_models::KinematicState* planning_scene_utils::MotionPlanRequestData::getGoalState | ( | ) |  [inline] | 
Returns a KinematicState pointer corresponding to the goal joint constraints of the robot.
Definition at line 567 of file move_arm_utils.h.
| std::string planning_scene_utils::MotionPlanRequestData::getGroupName | ( | ) | const  [inline] | 
Returns the name of the planning group associated with the motion plan request (usually, right or left arm)
Definition at line 574 of file move_arm_utils.h.
| unsigned int planning_scene_utils::MotionPlanRequestData::getId | ( | ) | const  [inline] | 
Definition at line 604 of file move_arm_utils.h.
| std::vector< std::string > MotionPlanRequestData::getJointNamesInGoal | ( | ) | 
Returns a vector of joint messages corresponding to all the joints in the goal constraints of the underlying motion plan request message.
Definition at line 670 of file move_arm_utils.cpp.
| tf::Transform planning_scene_utils::MotionPlanRequestData::getLastGoodGoalPose | ( | ) | const  [inline] | 
Returns the last goal pose that had a good IK solution.
Definition at line 493 of file move_arm_utils.h.
| tf::Transform planning_scene_utils::MotionPlanRequestData::getLastGoodStartPose | ( | ) | const  [inline] | 
Returns the last starting pose that had a good IK solution.
Definition at line 487 of file move_arm_utils.h.
| arm_navigation_msgs::MotionPlanRequest& planning_scene_utils::MotionPlanRequestData::getMotionPlanRequest | ( | ) |  [inline] | 
Gets the underlying motion plan request message.
Definition at line 776 of file move_arm_utils.h.
| const std::string& planning_scene_utils::MotionPlanRequestData::getName | ( | void | ) | const  [inline] | 
Returns the unique Id of the motion plan request.
Definition at line 599 of file move_arm_utils.h.
| unsigned int planning_scene_utils::MotionPlanRequestData::getNextTrajectoryId | ( | ) | const  [inline] | 
Definition at line 812 of file move_arm_utils.h.
| double planning_scene_utils::MotionPlanRequestData::getPitchTolerance | ( | ) | const  [inline] | 
Definition at line 869 of file move_arm_utils.h.
| unsigned int planning_scene_utils::MotionPlanRequestData::getPlanningSceneId | ( | ) | const  [inline] | 
Definition at line 795 of file move_arm_utils.h.
| std::string planning_scene_utils::MotionPlanRequestData::getPlanningSceneName | ( | ) | const  [inline] | 
Returns the unique planning scene Id that this motion plan request is associated with.
Definition at line 801 of file move_arm_utils.h.
| RenderType planning_scene_utils::MotionPlanRequestData::getRenderType | ( | ) | const  [inline] | 
Gets what mesh to display in RVIZ.
Definition at line 422 of file move_arm_utils.h.
| double planning_scene_utils::MotionPlanRequestData::getRollTolerance | ( | ) | const  [inline] | 
Definition at line 861 of file move_arm_utils.h.
| const std::string& planning_scene_utils::MotionPlanRequestData::getSource | ( | ) | const  [inline] | 
Returns the pipeline stage associated with this motion plan request.
Definition at line 770 of file move_arm_utils.h.
| const std_msgs::ColorRGBA& planning_scene_utils::MotionPlanRequestData::getStartColor | ( | ) | const  [inline] | 
Returns the color of the markers of the start position.
Definition at line 712 of file move_arm_utils.h.
| planning_models::KinematicState* planning_scene_utils::MotionPlanRequestData::getStartState | ( | ) |  [inline] | 
Returns a KinematicState pointer corresponding to the starting joint state of the robot.
Definition at line 561 of file move_arm_utils.h.
| std::set<unsigned int>& planning_scene_utils::MotionPlanRequestData::getTrajectories | ( | ) |  [inline] | 
Returns a vector of unique trajectory Ids associated with this motion plan request.
Definition at line 807 of file move_arm_utils.h.
| double planning_scene_utils::MotionPlanRequestData::getYawTolerance | ( | ) | const  [inline] | 
Definition at line 877 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::hasGoodIKSolution | ( | const PositionType & | type | ) | const  [inline] | 
Returns true if an IK solution was found for this request, and false otherwise.
Definition at line 541 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::hasPathConstraints | ( | ) | const  [inline] | 
Definition at line 829 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::hasRefreshedColors | ( | ) | const  [inline] | 
Returns true if the refresh counter has been exhausted, and false otherwise.
Definition at line 622 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::hasStateChanged | ( | ) | const  [inline] | 
Returns true if the joint values or the color of the motion plan request has changed.
Definition at line 445 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::hasTrajectoryId | ( | unsigned int | id | ) | const  [inline] | 
Definition at line 825 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::hide | ( | ) |  [inline] | 
Sets both the start and end positions to invisible.
Definition at line 681 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::hideCollisions | ( | ) |  [inline] | 
Convenience shorthand for setCollisionsVisible(false)
Definition at line 481 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::hideGoal | ( | ) |  [inline] | 
Shorthand for setEndVisible(false)
Definition at line 706 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::hideStart | ( | ) |  [inline] | 
Shorthand for setStartVisible(false)
Definition at line 700 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::isEndVisible | ( | ) | const  [inline] | 
Returns true if the goal kinematic state of the robot is being published as a set of markers or false otherwise.
Definition at line 656 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::isGoalEditable | ( | ) | const  [inline] | 
If true, then a 6DOF control and joint controls will be visible for the goal position of the robot. If false, these controls will not be shown.
Definition at line 758 of file move_arm_utils.h.
| bool MotionPlanRequestData::isJointNameInGoal | ( | std::string | joint | ) | 
returns whether or not the specified joint name is part of the goal constraints of the motion plan request.
| joint | a valid joint name. | 
Definition at line 685 of file move_arm_utils.cpp.
| bool planning_scene_utils::MotionPlanRequestData::isStartEditable | ( | ) | const  [inline] | 
If true, then a 6DOF control and joint controls will be visible for the start position of the robot. If false, these controls will not be shown.
Definition at line 751 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::isStartVisible | ( | ) | const  [inline] | 
Returns true if the starting kinematic state of the robot is being published as a set of markers or false otherwise.
Definition at line 649 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::refreshColors | ( | ) |  [inline] | 
Tell the planning scene editor to stop publishing markers for a while so that the colors of the motion plan request can be changed.
Definition at line 640 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::removeTrajectoryId | ( | unsigned int | id | ) |  [inline] | 
Definition at line 821 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::reset | ( | ) |  [inline] | 
Deletes the kinematic states associated with the motion plan request.
Definition at line 525 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setCollisionsVisible | ( | bool | visible | ) |  [inline] | 
Either show or hide the red spheres corresponding to collision points.
Definition at line 469 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setConstrainPitch | ( | bool | s | ) |  [inline] | 
Definition at line 849 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setConstrainRoll | ( | bool | s | ) |  [inline] | 
Definition at line 841 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setConstrainYaw | ( | bool | s | ) |  [inline] | 
Definition at line 857 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setEndEffectorLink | ( | const std::string & | name | ) |  [inline] | 
Sets the name of the link that IK is performed for.
Definition at line 593 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setEndVisible | ( | bool | visible | ) |  [inline] | 
see isEndVisible
Definition at line 668 of file move_arm_utils.h.
| void MotionPlanRequestData::setGoalAndPathPositionOrientationConstraints | ( | arm_navigation_msgs::MotionPlanRequest & | mpr, | 
| planning_scene_utils::PositionType | type | ||
| ) | const | 
Definition at line 517 of file move_arm_utils.cpp.
| void planning_scene_utils::MotionPlanRequestData::setGoalColor | ( | std_msgs::ColorRGBA | color | ) |  [inline] | 
Sets the color of the markers for the goal position.
Definition at line 730 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setGoalEditable | ( | bool | editable | ) |  [inline] | 
If true, then a 6DOF control and joint controls will be visible for the goal position of the robot. If false, these controls will not be shown.
Definition at line 744 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setGoalState | ( | planning_models::KinematicState * | state | ) |  [inline] | 
Sets the kinematic state corresponding to the goal joint state of the robot.
Definition at line 518 of file move_arm_utils.h.
| void MotionPlanRequestData::setGoalStateValues | ( | std::map< std::string, double > & | joint_values | ) | 
Sets the goal state joint values of the robot.
| joint_values | a map of joint names to values. | 
Definition at line 481 of file move_arm_utils.cpp.
| void planning_scene_utils::MotionPlanRequestData::setGroupName | ( | const std::string & | name | ) |  [inline] | 
Sets the name of the planning group associated with the motion plan request (usually, right or left arm)
Definition at line 587 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setHasGoodIKSolution | ( | const bool & | solution, | 
| const PositionType & | type | ||
| ) |  [inline] | 
Set whether or not an IK solution was found for the start or end of this request.
Definition at line 551 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setHasRefreshedColors | ( | bool | refresh | ) |  [inline] | 
See hasRefreshedColors.
Definition at line 628 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setId | ( | const unsigned int | id | ) |  [inline] | 
Sets the unique Id of the motion plan request.
Definition at line 609 of file move_arm_utils.h.
| void MotionPlanRequestData::setJointControlsVisible | ( | bool | visible, | 
| PlanningSceneEditor * | editor | ||
| ) | 
Either creates or destroys the interactive joint control markers for this request.
| visible | if true, creates the joint markers. If False, destroys them. | 
| editor | pointer to the planning scene editor responsible for maintaining the markers. | 
Definition at line 445 of file move_arm_utils.cpp.
| void planning_scene_utils::MotionPlanRequestData::setLastGoodGoalPose | ( | tf::Transform | pose | ) |  [inline] | 
Stores a poase as the last goal pose with a good IK solution.
Definition at line 505 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setLastGoodStartPose | ( | tf::Transform | pose | ) |  [inline] | 
Stores a pose as the last starting pose with a good IK solution.
Definition at line 499 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setMotionPlanRequest | ( | const arm_navigation_msgs::MotionPlanRequest & | request | ) |  [inline] | 
Sets the underlying motion plan request message.
Definition at line 782 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setPathConstraints | ( | bool | has | ) |  [inline] | 
Definition at line 833 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setPitchTolerance | ( | double | s | ) |  [inline] | 
Definition at line 873 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setPlanningSceneId | ( | const unsigned int | id | ) |  [inline] | 
Sets the planning scene Id that this motion plan request is associated with.
Definition at line 791 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setRenderType | ( | RenderType | renderType | ) |  [inline] | 
Sets what mesh to display in RVIZ.
Definition at line 428 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setRollTolerance | ( | double | s | ) |  [inline] | 
Definition at line 865 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setSource | ( | const std::string & | source | ) |  [inline] | 
Set the pipeline stage associated with this motion plan request.
Definition at line 764 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setStartColor | ( | std_msgs::ColorRGBA | color | ) |  [inline] | 
Sets the color of the markers for the start position.
Definition at line 724 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setStartEditable | ( | bool | editable | ) |  [inline] | 
If true, then a 6DOF control and joint controls will be visible for the start position of the robot. If false, these controls will not be shown.
Definition at line 737 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setStartState | ( | planning_models::KinematicState * | state | ) |  [inline] | 
Sets the kinematic state corresponding to the starting joint state of the robot.
Definition at line 511 of file move_arm_utils.h.
| void MotionPlanRequestData::setStartStateValues | ( | std::map< std::string, double > & | joint_values | ) | 
Sets the start state joint values of the robot.
| joint_values | a map of joint names to values. | 
Definition at line 475 of file move_arm_utils.cpp.
| void planning_scene_utils::MotionPlanRequestData::setStartVisible | ( | bool | visible | ) |  [inline] | 
see isStartVisible
Definition at line 662 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setStateChanged | ( | bool | changed | ) |  [inline] | 
Set the flag recording whether or not the joint state or color of the motion plan request has changed.
Definition at line 451 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::setYawTolerance | ( | double | s | ) |  [inline] | 
Definition at line 881 of file move_arm_utils.h.
| bool planning_scene_utils::MotionPlanRequestData::shouldRefreshColors | ( | ) | const  [inline] | 
Returns true if the motion plan request's colors have changed, and false otherwise.
Definition at line 616 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::show | ( | ) |  [inline] | 
Sets both the start and end positions to be published.
Definition at line 674 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::showCollisions | ( | ) |  [inline] | 
Convenience shorthand for setCollisionsVisible(true)
Definition at line 475 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::showGoal | ( | ) |  [inline] | 
Shorthand for setEndVisible(true)
Definition at line 694 of file move_arm_utils.h.
| void planning_scene_utils::MotionPlanRequestData::showStart | ( | ) |  [inline] | 
Shorthand for setStartVisible(true)
Definition at line 688 of file move_arm_utils.h.
| void MotionPlanRequestData::updateCollisionMarkers | ( | planning_environment::CollisionModels * | cm_, | 
| ros::ServiceClient * | distance_state_validity_service_client_ | ||
| ) | 
Fills the member marker array with small red spheres associated with collision points.
Definition at line 585 of file move_arm_utils.cpp.
Updates the KinematicState pointer goal_state_ to reflect changes to the underlying motion plan request message.
Definition at line 404 of file move_arm_utils.cpp.
Updates the KinematicState pointer start_state_ to reflect changes to the underlying motion plan request message.
Definition at line 440 of file move_arm_utils.cpp.
Definition at line 352 of file move_arm_utils.h.
Definition at line 354 of file move_arm_utils.h.
| visualization_msgs::MarkerArray planning_scene_utils::MotionPlanRequestData::collision_markers_  [protected] | 
Definition at line 371 of file move_arm_utils.h.
Definition at line 361 of file move_arm_utils.h.
Definition at line 360 of file move_arm_utils.h.
Definition at line 362 of file move_arm_utils.h.
| std::string planning_scene_utils::MotionPlanRequestData::end_effector_link_  [protected] | 
Definition at line 340 of file move_arm_utils.h.
| std_msgs::ColorRGBA planning_scene_utils::MotionPlanRequestData::goal_color_  [protected] | 
Definition at line 365 of file move_arm_utils.h.
| planning_models::KinematicState* planning_scene_utils::MotionPlanRequestData::goal_state_  [protected] | 
Definition at line 368 of file move_arm_utils.h.
| std::string planning_scene_utils::MotionPlanRequestData::group_name_  [protected] | 
Definition at line 341 of file move_arm_utils.h.
Definition at line 350 of file move_arm_utils.h.
Definition at line 351 of file move_arm_utils.h.
Definition at line 349 of file move_arm_utils.h.
Definition at line 348 of file move_arm_utils.h.
Definition at line 353 of file move_arm_utils.h.
| unsigned int planning_scene_utils::MotionPlanRequestData::id_  [protected] | 
Definition at line 337 of file move_arm_utils.h.
Definition at line 344 of file move_arm_utils.h.
Definition at line 346 of file move_arm_utils.h.
Definition at line 343 of file move_arm_utils.h.
Definition at line 345 of file move_arm_utils.h.
Definition at line 370 of file move_arm_utils.h.
Definition at line 369 of file move_arm_utils.h.
| arm_navigation_msgs::MotionPlanRequest planning_scene_utils::MotionPlanRequestData::motion_plan_request_  [protected] | 
Definition at line 342 of file move_arm_utils.h.
| std::string planning_scene_utils::MotionPlanRequestData::name_  [protected] | 
Definition at line 336 of file move_arm_utils.h.
| unsigned int planning_scene_utils::MotionPlanRequestData::next_trajectory_id_  [protected] | 
Definition at line 373 of file move_arm_utils.h.
| double planning_scene_utils::MotionPlanRequestData::pitch_tolerance_  [protected] | 
Definition at line 357 of file move_arm_utils.h.
| unsigned int planning_scene_utils::MotionPlanRequestData::planning_scene_id_  [protected] | 
Definition at line 339 of file move_arm_utils.h.
If the color of the motion plan request changes, this counter is incremented until it reaches a value specified by the planning scene editor. This is done to allow the display markers time to disappear before their colors are changed.
Definition at line 392 of file move_arm_utils.h.
Definition at line 372 of file move_arm_utils.h.
| double planning_scene_utils::MotionPlanRequestData::roll_tolerance_  [protected] | 
Definition at line 356 of file move_arm_utils.h.
Definition at line 347 of file move_arm_utils.h.
| std::string planning_scene_utils::MotionPlanRequestData::source_  [protected] | 
Definition at line 338 of file move_arm_utils.h.
| std_msgs::ColorRGBA planning_scene_utils::MotionPlanRequestData::start_color_  [protected] | 
Definition at line 364 of file move_arm_utils.h.
| planning_models::KinematicState* planning_scene_utils::MotionPlanRequestData::start_state_  [protected] | 
Definition at line 367 of file move_arm_utils.h.
| std::set<unsigned int> planning_scene_utils::MotionPlanRequestData::trajectories_  [protected] | 
Definition at line 366 of file move_arm_utils.h.
| double planning_scene_utils::MotionPlanRequestData::yaw_tolerance_  [protected] | 
Definition at line 358 of file move_arm_utils.h.