moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Static Public Member Functions | List of all members
moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy Class Referencefinal

A cache insertion policy that only decides to insert if the motion plan is the one with the shortest execution time seen so far amongst exactly matching GetCartesianPath requests. More...

#include <best_seen_execution_time_policy.hpp>

Inheritance diagram for moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy:
Inheritance graph
[legend]
Collaboration diagram for moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy:
Collaboration graph
[legend]

Public Member Functions

 CartesianBestSeenExecutionTimePolicy ()
 
std::string getName () const override
 Gets the name of the cache insert policy.
 
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.
 
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.
 
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
 
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.
 
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.
 
void reset () override
 Resets the state of the policy.
 
- Public Member Functions inherited from moveit_ros::trajectory_cache::CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory >
virtual ~CacheInsertPolicyInterface ()=default
 
virtual bool shouldPruneMatchingEntry (const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, const typename warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr &matching_entry, std::string *reason)=0
 Returns whether a matched cache entry should be pruned.
 

Static Public Member 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.
 

Detailed Description

A cache insertion policy that only decides to insert if the motion plan is the one with the shortest execution time seen so far amongst exactly matching GetCartesianPath requests.

Supported Metadata and Features ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Appends the following additional metadata, which can be used for querying and sorting:

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:

See also
get_cartesian_path_request_features.hpp
constant_features.hpp
FeaturesInterface<FeatureSourceT>

Matches and Pruning ^^^^^^^^^^^^^^^^^^^ A matching cache entry is one that has a GetCartesianPath request that exactly matches on every one of the features above.

The sort order is ordered on execution_time_s in ascending order (so loweest execution time first).

This policy indicates that pruning should happen if there are any exactly matching plans that are worse than the insertion candidate.

REMINDER: The TrajectoryCache still decides to honor the prune indication or not, based off the parameters passed to the insert call.

Insertion ^^^^^^^^^ This policy indicates that insertion should happen if the candidate plan is the best seen in terms of shortest execution time than other plans with exactly matching GetCartesianPath requests.

This policy aggregates state in the fetchMatchingEntries call to facilitate this.

Definition at line 194 of file best_seen_execution_time_policy.hpp.

Constructor & Destructor Documentation

◆ CartesianBestSeenExecutionTimePolicy()

moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::CartesianBestSeenExecutionTimePolicy ( )

Definition at line 271 of file best_seen_execution_time_policy.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ appendInsertMetadata()

MoveItErrorCode moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::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 
)
overridevirtual

Appends the insert metadata with the features supported by the policy.

See notes in docstrings regarding the feature contract.

Parameters
[in,out]metadata.The metadata to add features to.
[in]move_group.The manipulator move group, used to get its state.
[in]key.The object used to key the insertion candidate with.
[in]value.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.

Implements moveit_ros::trajectory_cache::CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory >.

Definition at line 441 of file best_seen_execution_time_policy.cpp.

Here is the call graph for this function:

◆ checkCacheInsertInputs()

MoveItErrorCode moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::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 
)
overridevirtual

Checks inputs to the cache insert call to see if we should abort instead.

Parameters
[in]move_group.The manipulator move group, used to get its state.
[in]coll.The cache database to fetch messages from.
[in]key.The object used to key the insertion candidate with.
[in]value.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.

Implements moveit_ros::trajectory_cache::CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory >.

Definition at line 307 of file best_seen_execution_time_policy.cpp.

Here is the call graph for this function:

◆ fetchMatchingEntries()

std::vector< MessageWithMetadata< RobotTrajectory >::ConstPtr > moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::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 
)
overridevirtual

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.

See also
CacheInsertPolicyInterface<KeyT, ValueT, CacheEntryT>::shouldPruneMatchingEntry
Parameters
[in]move_group.The manipulator move group, used to get its state.
[in]coll.The cache database to fetch messages from.
[in]key.The object used to key the insertion candidate with.
[in]value.The object that the TrajectoryCache was passed to insert.
[in]exact_match_precision.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.

Implements moveit_ros::trajectory_cache::CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory >.

Definition at line 355 of file best_seen_execution_time_policy.cpp.

◆ getName()

std::string moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::getName ( ) const
overridevirtual

◆ getSupportedFeatures()

std::vector< std::unique_ptr< FeaturesInterface< GetCartesianPath::Request > > > moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::getSupportedFeatures ( double  start_tolerance,
double  goal_tolerance,
double  min_fraction 
)
static

Configures and returns a vector of feature extractors that can be used with this policy.

Definition at line 280 of file best_seen_execution_time_policy.cpp.

Here is the caller graph for this function:

◆ reset()

void moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::reset ( )
overridevirtual

◆ shouldInsert()

bool moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::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 
)
overridevirtual

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
[in]move_group.The manipulator move group, used to get its state.
[in]key.The object used to key the insertion candidate with.
[in]value.The object that the TrajectoryCache was passed to insert.
[out]reason.The reason for the returned result.
Returns
True if the insertion candidate should be inserted into the cache.

Implements moveit_ros::trajectory_cache::CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory >.

Definition at line 411 of file best_seen_execution_time_policy.cpp.

Here is the call graph for this function:

◆ shouldPruneMatchingEntry()

bool moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy::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

Definition at line 379 of file best_seen_execution_time_policy.cpp.

Here is the call graph for this function:

The documentation for this class was generated from the following files: