Class CartesianAlwaysInsertNeverPrunePolicy
Defined in File always_insert_never_prune_policy.hpp
Inheritance Relationships
Base Type
public moveit_ros::trajectory_cache::CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory >
(Template Class CacheInsertPolicyInterface)
Class Documentation
-
class CartesianAlwaysInsertNeverPrunePolicy : public moveit_ros::trajectory_cache::CacheInsertPolicyInterface<moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory>
A cache insertion policy that always decides to insert and never decides to prune for cartesian path requests.
Supported Metadata and Features ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Appends the following additional metadata, which can be used for querying and sorting:
fraction
execution_time_s
NOTE: Planning time is not available. If you want to use it, add it as an additional MetadataOnly feature in the cache insert call.
Compatible with the get cartesian path request features:
Matches, Pruning, and Insertion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ A matching cache entry is one that exactly matches on every one of the features above, and fraction.
See also
get_cartesian_path_request_features.hpp
See also
constant_features.hpp
See also
FeaturesInterface<FeatureSourceT>
The sort order is ordered on execution_time_s in ascending order (so loweest execution time first). This policy never indicates that pruning should happen, and always indicates that insertion should happen.
Public Functions
-
CartesianAlwaysInsertNeverPrunePolicy()
-
virtual std::string getName() const override
Gets the name of the cache insert policy.
-
virtual moveit::core::MoveItErrorCode checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory> &coll, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value) override
Checks inputs to the cache insert call to see if we should abort instead.
- Parameters:
move_group. – [in] The manipulator move group, used to get its state.
coll. – [in] The cache database to fetch messages from.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
- Returns:
moveit::core::MoveItErrorCode::SUCCESS if the cache insert should proceed. Otherwise, will return a different error code with the reason why it should not.
-
virtual std::vector<warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr> fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory> &coll, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, double exact_match_precision) override
Fetches all “matching” cache entries for comparison for pruning.
This method should be assumed to only return the message metadata without the underlying message data.
The policy should also make the decision about how to sort them. The order in which cache entries are presented to the shouldPruneMatchingEntry will be the order of cache entries returned by this function.
- Parameters:
move_group. – [in] The manipulator move group, used to get its state.
coll. – [in] The cache database to fetch messages from.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
exact_match_precision. – [in] Tolerance for float precision comparison for what counts as an exact match.
- Returns:
A vector of only the metadata of matching cache entries for use by the other methods.
-
bool shouldPruneMatchingEntry(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, const warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr &matching_entry, std::string *reason = nullptr) override
-
virtual bool shouldInsert(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, std::string *reason = nullptr) override
Returns whether the insertion candidate should be inserted into the cache.
NOTE: The TrajectoryCache class executes the insert, but this class informs it on whether the insert should happen or not.
- Parameters:
move_group. – [in] The manipulator move group, used to get its state.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
reason. – [out] The reason for the returned result.
- Returns:
True if the insertion candidate should be inserted into the cache.
-
virtual moveit::core::MoveItErrorCode appendInsertMetadata(warehouse_ros::Metadata &metadata, const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value) override
Appends the insert metadata with the features supported by the policy.
See notes in docstrings regarding the feature contract.
- Parameters:
metadata. – [inout] The metadata to add features to.
move_group. – [in] The manipulator move group, used to get its state.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
- Returns:
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the metadata should not be reused, and the TrajectoryCache will abort the insert.
-
virtual void reset() override
Resets the state of the policy.
Public Static Functions
-
static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>> getSupportedFeatures(double start_tolerance, double goal_tolerance, double min_fraction)
Configures and returns a vector of feature extractors that can be used with this policy.