Class GoalConstraintsFeatures

Inheritance Relationships

Base Type

Class Documentation

class GoalConstraintsFeatures : public moveit_ros::trajectory_cache::FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>

Extracts features from the goal_constraints field in the plan request.

See also

appendConstraintsAsFetchQueryWithTolerance

See also

appendConstraintsAsInsertMetadata

Public Functions

GoalConstraintsFeatures(double match_tolerance)
virtual std::string getName() const override

Gets the name of the features implementation.

virtual moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override

Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.

These parameters will be used key the cache element in a fuzzy manner.

Parameters:
  • query.[inout] The query to add features to.

  • source.[in] A FeatureSourceT to extract features from.

  • move_group.[in] The manipulator move group, used to get its state.

  • exact_match_precision.[in] Tolerance for float precision comparison for what counts as an exact match.

Returns:

moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the query should not be reused.

virtual moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override

Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.

These parameters will be used key the cache element in an exact manner.

Parameters:
  • query.[inout] The query to add features to.

  • source.[in] A FeatureSourceT to extract features from.

  • move_group.[in] The manipulator move group, used to get its state.

  • exact_match_precision.[in] Tolerance for float precision comparison for what counts as an exact match.

Returns:

moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the query should not be reused.

virtual moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override

Extracts relevant features from FeatureSourceT, to be appended to a cache entry’s metadata.

These parameters will be used key the cache element.

Parameters:
  • metadata.[inout] The metadata to add features to.

  • source.[in] A FeatureSourceT to extract features from.

  • move_group.[in] The manipulator move group, used to get its state.

Returns:

moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the metadata should not be reused.