$search

planning_scene_utils::MotionPlanRequestData Class Reference

Convenience class wrapping a motion plan request and its meta-data. More...

#include <move_arm_utils.h>

List of all members.

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::MarkerArraygetCollisionMarkers ()
 Each motion plan request stores an array of small red spheres corresponding to collision points.
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::KinematicStategetGoalState ()
 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.
btTransform getLastGoodGoalPose () const
 Returns the last goal pose that had a good IK solution.
btTransform getLastGoodStartPose () const
 Returns the last starting pose that had a good IK solution.
arm_navigation_msgs::MotionPlanRequestgetMotionPlanRequest ()
 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
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.
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::KinematicStategetStartState ()
 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.
bool hasGoodIKSolution (const PositionType &type) const
 Returns true if an IK solution was found for this request, and false otherwise.
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 (const unsigned int &id, const std::string &source, const arm_navigation_msgs::MotionPlanRequest &request, const planning_models::KinematicState *robot_state)
 MotionPlanRequestData (const planning_models::KinematicState *robot_state)
 MotionPlanRequestData ()
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 setEndEffectorLink (const std::string &name)
 Sets the name of the link that IK is performed for.
void setEndVisible (bool visible)
 see isEndVisible
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 (btTransform pose)
 Stores a poase as the last goal pose with a good IK solution.
void setLastGoodStartPose (btTransform 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 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 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.
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_
std::string end_effector_link_
std_msgs::ColorRGBA goal_color_
planning_models::KinematicStategoal_state_
std::string group_name_
bool has_good_goal_ik_solution_
bool has_good_start_ik_solution_
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_
btTransform last_good_goal_pose_
btTransform last_good_start_pose_
arm_navigation_msgs::MotionPlanRequest motion_plan_request_
std::string name_
unsigned int next_trajectory_id_
unsigned int planning_scene_id_
RenderType render_type_
bool should_refresh_colors_
std::string source_
std_msgs::ColorRGBA start_color_
planning_models::KinematicStatestart_state_
std::set< unsigned int > trajectories_

Detailed Description

Convenience class wrapping a motion plan request and its meta-data.

Class MotionPlanRequestData

Definition at line 275 of file move_arm_utils.h.


Constructor & Destructor Documentation

planning_scene_utils::MotionPlanRequestData::MotionPlanRequestData (  )  [inline]

Definition at line 308 of file move_arm_utils.h.

MotionPlanRequestData::MotionPlanRequestData ( const planning_models::KinematicState robot_state  ) 

Definition at line 231 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 
)

Member Function Documentation

void planning_scene_utils::MotionPlanRequestData::addTrajectoryId ( unsigned int  id  )  [inline]

Definition at line 746 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 392 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 363 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 386 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 509 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 647 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 496 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 503 of file move_arm_utils.h.

unsigned int planning_scene_utils::MotionPlanRequestData::getId (  )  const [inline]

Definition at line 533 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 433 of file move_arm_utils.cpp.

btTransform planning_scene_utils::MotionPlanRequestData::getLastGoodGoalPose (  )  const [inline]

Returns the last goal pose that had a good IK solution.

Definition at line 422 of file move_arm_utils.h.

btTransform planning_scene_utils::MotionPlanRequestData::getLastGoodStartPose (  )  const [inline]

Returns the last starting pose that had a good IK solution.

Definition at line 416 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 705 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 528 of file move_arm_utils.h.

unsigned int planning_scene_utils::MotionPlanRequestData::getNextTrajectoryId (  )  const [inline]

Definition at line 741 of file move_arm_utils.h.

unsigned int planning_scene_utils::MotionPlanRequestData::getPlanningSceneId (  )  const [inline]

Definition at line 724 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 730 of file move_arm_utils.h.

RenderType planning_scene_utils::MotionPlanRequestData::getRenderType (  )  const [inline]

Gets what mesh to display in RVIZ.

Definition at line 351 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 699 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 641 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 490 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 736 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 470 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 551 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 374 of file move_arm_utils.h.

bool planning_scene_utils::MotionPlanRequestData::hasTrajectoryId ( unsigned int  id  )  const [inline]

Definition at line 754 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 610 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::hideCollisions (  )  [inline]

Convenience shorthand for setCollisionsVisible(false).

Definition at line 410 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::hideGoal (  )  [inline]

Shorthand for setEndVisible(false).

Definition at line 635 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::hideStart (  )  [inline]

Shorthand for setStartVisible(false).

Definition at line 629 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 585 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 687 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.

Parameters:
joint a valid joint name.
Returns:
true if the joint with the specified name is in the goal constraints, and false otherwise

Definition at line 448 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 680 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 578 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 569 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::removeTrajectoryId ( unsigned int  id  )  [inline]

Definition at line 750 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 454 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 398 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 522 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::setEndVisible ( bool  visible  )  [inline]

see isEndVisible

Definition at line 597 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::setGoalColor ( std_msgs::ColorRGBA  color  )  [inline]

Sets the color of the markers for the goal position.

Definition at line 659 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 673 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 447 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.

Parameters:
joint_values a map of joint names to values.

Definition at line 340 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 516 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 480 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::setHasRefreshedColors ( bool  refresh  )  [inline]

See hasRefreshedColors.

Definition at line 557 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 538 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.

Parameters:
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 304 of file move_arm_utils.cpp.

void planning_scene_utils::MotionPlanRequestData::setLastGoodGoalPose ( btTransform  pose  )  [inline]

Stores a poase as the last goal pose with a good IK solution.

Definition at line 434 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::setLastGoodStartPose ( btTransform  pose  )  [inline]

Stores a pose as the last starting pose with a good IK solution.

Definition at line 428 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 711 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 720 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 357 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 693 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 653 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 666 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 440 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.

Parameters:
joint_values a map of joint names to values.

Definition at line 334 of file move_arm_utils.cpp.

void planning_scene_utils::MotionPlanRequestData::setStartVisible ( bool  visible  )  [inline]

see isStartVisible

Definition at line 591 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 380 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 545 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 603 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::showCollisions (  )  [inline]

Convenience shorthand for setCollisionsVisible(true).

Definition at line 404 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::showGoal (  )  [inline]

Shorthand for setEndVisible(true).

Definition at line 623 of file move_arm_utils.h.

void planning_scene_utils::MotionPlanRequestData::showStart (  )  [inline]

Shorthand for setStartVisible(true).

Definition at line 617 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 356 of file move_arm_utils.cpp.

void MotionPlanRequestData::updateGoalState (  ) 

Updates the KinematicState pointer goal_state_ to reflect changes to the underlying motion plan request message.

Definition at line 283 of file move_arm_utils.cpp.

void MotionPlanRequestData::updateStartState (  ) 

Updates the KinematicState pointer start_state_ to reflect changes to the underlying motion plan request message.

Definition at line 299 of file move_arm_utils.cpp.


Member Data Documentation

Definition at line 293 of file move_arm_utils.h.

Definition at line 295 of file move_arm_utils.h.

Definition at line 303 of file move_arm_utils.h.

Definition at line 282 of file move_arm_utils.h.

Definition at line 297 of file move_arm_utils.h.

Definition at line 300 of file move_arm_utils.h.

Definition at line 283 of file move_arm_utils.h.

Definition at line 291 of file move_arm_utils.h.

Definition at line 292 of file move_arm_utils.h.

Definition at line 290 of file move_arm_utils.h.

Definition at line 294 of file move_arm_utils.h.

Definition at line 279 of file move_arm_utils.h.

Definition at line 286 of file move_arm_utils.h.

Definition at line 288 of file move_arm_utils.h.

Definition at line 285 of file move_arm_utils.h.

Definition at line 287 of file move_arm_utils.h.

Definition at line 302 of file move_arm_utils.h.

Definition at line 301 of file move_arm_utils.h.

Definition at line 284 of file move_arm_utils.h.

Definition at line 278 of file move_arm_utils.h.

Definition at line 305 of file move_arm_utils.h.

Definition at line 281 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 321 of file move_arm_utils.h.

Definition at line 304 of file move_arm_utils.h.

Definition at line 289 of file move_arm_utils.h.

Definition at line 280 of file move_arm_utils.h.

Definition at line 296 of file move_arm_utils.h.

Definition at line 299 of file move_arm_utils.h.

Definition at line 298 of file move_arm_utils.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


move_arm_warehouse
Author(s): Ioan Sucan, Sachin Chitta(sachinc@willowgarage.com)
autogenerated on Fri Mar 1 15:11:44 2013