Skip to content

Commit 1feb211

Browse files
committed
Add CacheInsertPolicyInterface and AlwaysInsertNeverPrunePolicy
Signed-off-by: methylDragon <[email protected]>
1 parent ea3e333 commit 1feb211

File tree

7 files changed

+823
-4
lines changed

7 files changed

+823
-4
lines changed

moveit_ros/trajectory_cache/CMakeLists.txt

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ set(TRAJECTORY_CACHE_DEPENDENCIES
3434

3535
set(TRAJECTORY_CACHE_LIBRARIES moveit_ros_trajectory_cache_utils_lib
3636
moveit_ros_trajectory_cache_features_lib
37+
moveit_ros_trajectory_cache_cache_insert_policies_lib
3738
moveit_ros_trajectory_cache_lib)
3839

3940
# Utils library
@@ -60,6 +61,19 @@ target_include_directories(
6061
ament_target_dependencies(moveit_ros_trajectory_cache_features_lib
6162
${TRAJECTORY_CACHE_DEPENDENCIES})
6263

64+
# Cache insert policies library
65+
add_library(moveit_ros_trajectory_cache_cache_insert_policies_lib
66+
src/cache_insert_policies/always_insert_never_prune_policy.cpp)
67+
generate_export_header(moveit_ros_trajectory_cache_cache_insert_policies_lib)
68+
target_link_libraries(moveit_ros_trajectory_cache_cache_insert_policies_lib
69+
moveit_ros_trajectory_cache_utils_lib)
70+
target_include_directories(
71+
moveit_ros_trajectory_cache_cache_insert_policies_lib
72+
PUBLIC $<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
73+
$<INSTALL_INTERFACE:include/moveit_ros_trajectory_cache>)
74+
ament_target_dependencies(moveit_ros_trajectory_cache_cache_insert_policies_lib
75+
${TRAJECTORY_CACHE_DEPENDENCIES})
76+
6377
# Trajectory cache library
6478
add_library(moveit_ros_trajectory_cache_lib src/trajectory_cache.cpp)
6579
generate_export_header(moveit_ros_trajectory_cache_lib)
Lines changed: 119 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,119 @@
1+
// Copyright 2024 Intrinsic Innovation LLC.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/** @file
16+
* @brief A cache insertion policy that always decides to insert and never decides to prune for motion plan requests.
17+
18+
* This is mainly for explanatory purposes.
19+
* @see CacheInsertPolicyInterface<KeyT, ValueT, CacheEntryT>
20+
*
21+
* @author methylDragon
22+
*/
23+
24+
#pragma once
25+
26+
#include <memory>
27+
28+
#include <warehouse_ros/message_collection.h>
29+
#include <moveit/move_group_interface/move_group_interface.h>
30+
#include <moveit_msgs/msg/motion_plan_request.hpp>
31+
32+
#include <moveit/trajectory_cache/cache_insert_policies/cache_insert_policy_interface.hpp>
33+
#include <moveit/trajectory_cache/features/features_interface.hpp>
34+
35+
namespace moveit_ros
36+
{
37+
namespace trajectory_cache
38+
{
39+
40+
// moveit_msgs::msg::MotionPlanRequest <=> moveit::planning_interface::MoveGroupInterface::Plan ====
41+
42+
/** @class AlwaysInsertNeverPrunePolicy
43+
*
44+
* @brief A cache insertion policy that always decides to insert and never decides to prune for motion plan requests.
45+
*
46+
* Supported Metadata and Features
47+
* ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
48+
* Appends the following additional metadata, which can be used for querying and sorting:
49+
* - execution_time_s
50+
* - planning_time_s
51+
*
52+
* Usable with the motion plan request features:
53+
* - WorkspaceFeatures
54+
* - StartStateJointStateFeatures
55+
* - MaxSpeedAndAccelerationFeatures
56+
* - GoalConstraintsFeatures
57+
* - PathConstraintsFeatures
58+
* - TrajectoryConstraintsFeatures
59+
*
60+
* @see motion_plan_request_features.hpp
61+
* @see FeaturesInterface<FeatureSourceT>
62+
*
63+
* Matches, Pruning, and Insertion
64+
* ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
65+
* A matching cache entry is one that exactly matches on every one of the features above.
66+
*
67+
* The sort order is ordered on execution_time_s in ascending order (so loweest execution time first).
68+
* This policy never indicates that pruning should happen, and always indicates that insertion should happen.
69+
*/
70+
class AlwaysInsertNeverPrunePolicy final
71+
: public CacheInsertPolicyInterface<moveit_msgs::msg::MotionPlanRequest,
72+
moveit::planning_interface::MoveGroupInterface::Plan,
73+
moveit_msgs::msg::RobotTrajectory>
74+
{
75+
public:
76+
/** @brief Configures and returns a vector of feature extractors that can be used with this policy. */
77+
static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>>
78+
getSupportedFeatures(double start_tolerance, double goal_tolerance);
79+
80+
AlwaysInsertNeverPrunePolicy();
81+
82+
std::string getName() const override;
83+
84+
moveit::core::MoveItErrorCode
85+
checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface& move_group,
86+
const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
87+
const moveit_msgs::msg::MotionPlanRequest& key,
88+
const moveit::planning_interface::MoveGroupInterface::Plan& value) override;
89+
90+
std::vector<warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr>
91+
fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface& move_group,
92+
const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
93+
const moveit_msgs::msg::MotionPlanRequest& key,
94+
const moveit::planning_interface::MoveGroupInterface::Plan& value,
95+
double exact_match_precision) override;
96+
97+
bool prunePredicate(
98+
const moveit::planning_interface::MoveGroupInterface& move_group, const moveit_msgs::msg::MotionPlanRequest& key,
99+
const moveit::planning_interface::MoveGroupInterface::Plan& value,
100+
const warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr& matched_entry) override;
101+
102+
bool insertPredicate(const moveit::planning_interface::MoveGroupInterface& move_group,
103+
const moveit_msgs::msg::MotionPlanRequest& key,
104+
const moveit::planning_interface::MoveGroupInterface::Plan& value) override;
105+
106+
moveit::core::MoveItErrorCode
107+
appendInsertMetadata(warehouse_ros::Metadata& metadata,
108+
const moveit::planning_interface::MoveGroupInterface& move_group,
109+
const moveit_msgs::msg::MotionPlanRequest& key,
110+
const moveit::planning_interface::MoveGroupInterface::Plan& value) override;
111+
112+
void reset() override;
113+
114+
private:
115+
const std::string name_;
116+
};
117+
118+
} // namespace trajectory_cache
119+
} // namespace moveit_ros
Lines changed: 205 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,205 @@
1+
// Copyright 2024 Intrinsic Innovation LLC.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/* Author: methylDragon */
16+
17+
#pragma once
18+
19+
#include <warehouse_ros/message_collection.h>
20+
#include <moveit/move_group_interface/move_group_interface.h>
21+
22+
namespace moveit_ros
23+
{
24+
namespace trajectory_cache
25+
{
26+
27+
/** @class CacheInsertPolicyInterface<KeyT, ValueT, CacheEntryT>
28+
* @headerfile cache_insert_policy_interface.hpp
29+
* "moveit/trajectory_cache/cache_insert_policies/cache_insert_policy_interface.hpp"
30+
*
31+
* @brief Abstract class for injecting logic for determining when to prune and insert a cache entry, and what metadata
32+
* to attach to the cache entry.
33+
*
34+
* @tparam KeyT. The object to extract features from which to key the cache. Typically the plan request.
35+
* @tparam ValueT. The object that the TrajectoryCache was passed to insert. Typically the plan response.
36+
* @tparam CacheEntryT. The actual type of the cache entry.
37+
*
38+
* Notably, implementations of this interface are used to determine all the logic leading up to, but not including, the
39+
* insert call itself.
40+
*
41+
* Additionally, the choice of which implementation to use will constraint the set of FeaturesInterface<FeatureSourceT>
42+
* implementations that can be used to fetch cache entries with, with a caveat mentioned later.
43+
*
44+
* Users may implement this interface to add additional cache insertion functionality beyond the ones provided by this
45+
* package (e.g., prioritizing minimum jerk, or minimal path length), and the set of metadata considered when inserting
46+
* the cache entry.
47+
*
48+
* @see TrajectoryCache
49+
* @see FeaturesInterface<FeatureSourceT>
50+
*
51+
* Usage
52+
* ^^^^^
53+
* Each policy makes certain decisions about what pieces of metadata to attach to the cache
54+
* entry for later fetching.
55+
*
56+
* As such, an implementation will necessarily constrain the set of FeaturesInterface<FeatureSourceT> implementations
57+
* that can be used to fetch entries from the cache that were tagged by a policy.
58+
*
59+
* There is no way to meaningfully express this coupling at compile time, so users must ensure that they read the
60+
* documentation of each implementation of the interface to determine what FeaturesInterface<FeatureSourceT>
61+
* implementations can be used with cache entries processed by the implementation.
62+
*
63+
* Two mitigations may be applied to alleviate this:
64+
* 1. Implementations of this interface may expose helper methods that can be called at runtime that take in arbitrary
65+
* configuration parameters to them initialize the features that are used to fetch cache entries at point of use.
66+
*
67+
* 2. The TrajectoryCache class' insertion methods allow the bubbling down of additional user-specified features to
68+
* be appended by the TrajectoryCache independent of a policy, which can be used to
69+
* support features that are not explicitly supported by the policy.
70+
*
71+
* Care must be taken to ensure that there are no overlaps when doing so, though, because it could potentially
72+
* result in duplicate metadata entries otherwise.
73+
*
74+
* Consequently, a set of FeaturesInterface<FeatureSourceT> implementations can be used to fetch a cache entry if that
75+
* set is a subset of the union of:
76+
* - The `additional_features` passed to `TrajectoryCache`
77+
* - The features used by a policy to append metadata to the cache entry
78+
*
79+
* Pruning and Insertion
80+
* ^^^^^^^^^^^^^^^^^^^^^
81+
* Pruning is a two step process:
82+
* 1. Fetch all "matching" cache entries, as defined by the policy
83+
* 2. From the fetched "matching" entries, subject each to the `prunePredicate` method, again defined by the
84+
* policy.
85+
*
86+
* This allows a user to define a policy to match and prune on any arbitrary properties of
87+
* the cache entries and insertion candidate.
88+
*
89+
* Similarly, logic can be injected to determine when the insertion candidate should be inserted.
90+
*
91+
* NOTE: The TrajectoryCache class also has some top-level logic to preserve cache entries that would have been pruned.
92+
*
93+
* Stateful Policies
94+
* ^^^^^^^^^^^^^^^^^
95+
* Finally, as there can be information that must be preserved across the multiple steps of the match-prune-insert
96+
* process, this interface assumes stateful operation within a single insert call.
97+
*
98+
* For example, preserving information in state will be required to propagate aggregated or rollup information about the
99+
* entire set of matched cache entries to future calls.
100+
*
101+
* The TrajectoryCache will call `reset()` on the policy at the end of the insert call.
102+
*
103+
* Call Flow
104+
* ^^^^^^^^^
105+
* The TrajectoryCache will call the following interface methods in the following order:
106+
* 1. sanitize, once
107+
* 2. fetchMatchingEntries, once
108+
* 3. prunePredicate, once per fetched entry from fetchMatchingEntries
109+
* 4. insertPredicate, once
110+
* 5. appendInsertMetadata, once, if insertPredicate returns true
111+
* 6. reset, once, at the end.
112+
*/
113+
template <typename KeyT, typename ValueT, typename CacheEntryT>
114+
class CacheInsertPolicyInterface
115+
{
116+
public:
117+
virtual ~CacheInsertPolicyInterface() = default;
118+
119+
/** @brief Gets the name of the cache insert policy. */
120+
virtual std::string getName() const = 0;
121+
122+
/** @brief Checks inputs to the cache insert call to see if we should abort instead.
123+
124+
* @param[in] move_group. The manipulator move group, used to get its state.
125+
* @param[in] coll. The cache database to fetch messages from.
126+
* @param[in] key. The object used to key the insertion candidate with.
127+
* @param[in] value. The object that the TrajectoryCache was passed to insert.
128+
* @returns moveit::core::MoveItErrorCode::SUCCESS if the cache insert should proceed. Otherwise, will return a
129+
different error code with the reason why it should not.
130+
*/
131+
virtual moveit::core::MoveItErrorCode
132+
checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface& move_group,
133+
const warehouse_ros::MessageCollection<CacheEntryT>& coll, const KeyT& key,
134+
const ValueT& value) = 0;
135+
136+
/** @brief Fetches all "matching" cache entries for comparison for pruning.
137+
*
138+
* The policy should also make the decision about how to sort them.
139+
* The order in which cache entries are presented to the prunePredicate will be the order of cache entries returned by
140+
* this function.
141+
*
142+
* @see CacheInsertPolicyInterface<KeyT, ValueT, CacheEntryT>#prunePredicate
143+
*
144+
* @param[in] move_group. The manipulator move group, used to get its state.
145+
* @param[in] coll. The cache database to fetch messages from.
146+
* @param[in] key. The object used to key the insertion candidate with.
147+
* @param[in] value. The object that the TrajectoryCache was passed to insert.
148+
* @param[in] exact_match_precision. Tolerance for float precision comparison for what counts as an exact match.
149+
* @returns A vector of matching cache entries for use by the other methods.
150+
*/
151+
virtual std::vector<typename warehouse_ros::MessageWithMetadata<CacheEntryT>::ConstPtr>
152+
fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface& move_group,
153+
const warehouse_ros::MessageCollection<CacheEntryT>& coll, const KeyT& key, const ValueT& value,
154+
double exact_match_precision) = 0;
155+
156+
/** @brief Returns whether a matched cache entry should be pruned.
157+
*
158+
* NOTE: The TrajectoryCache class also has some top-level logic to preserve cache entries that would have been
159+
* pruned.
160+
*
161+
* @param[in] move_group. The manipulator move group, used to get its state.
162+
* @param[in] key. The object used to key the insertion candidate with.
163+
* @param[in] value. The object that the TrajectoryCache was passed to insert.
164+
* @param[in] matched_entry. The matched cache entry to be possibly pruned.
165+
* @returns True if the cache entry should be pruned.
166+
*/
167+
virtual bool
168+
prunePredicate(const moveit::planning_interface::MoveGroupInterface& move_group, const KeyT& key, const ValueT& value,
169+
const typename warehouse_ros::MessageWithMetadata<CacheEntryT>::ConstPtr& matched_entry) = 0;
170+
171+
/** @brief Returns whether the insertion candidate should be inserted into the cache.
172+
*
173+
* NOTE: The TrajectoryCache class executes the insert, but this class informs it on whether the insert should happen
174+
* or not.
175+
*
176+
* @param[in] move_group. The manipulator move group, used to get its state.
177+
* @param[in] key. The object used to key the insertion candidate with.
178+
* @param[in] value. The object that the TrajectoryCache was passed to insert.
179+
* @returns True if the insertion candidate should be inserted into the cache.
180+
*/
181+
virtual bool insertPredicate(const moveit::planning_interface::MoveGroupInterface& move_group, const KeyT& key,
182+
const ValueT& value) = 0;
183+
184+
/** @brief Appends the insert metadata with the features supported by the policy.
185+
*
186+
* See notes in docstrings regarding the feature contract.
187+
*
188+
* @param[in,out] metadata. The metadata to add features to.
189+
* @param[in] move_group. The manipulator move group, used to get its state.
190+
* @param[in] key. The object used to key the insertion candidate with.
191+
* @param[in] value. The object that the TrajectoryCache was passed to insert.
192+
* @returns moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error
193+
* code, in which case the metadata should not be reused, and the TrajectoryCache will abort the insert.
194+
*/
195+
virtual moveit::core::MoveItErrorCode
196+
appendInsertMetadata(warehouse_ros::Metadata& metadata,
197+
const moveit::planning_interface::MoveGroupInterface& move_group, const KeyT& key,
198+
const ValueT& value) = 0;
199+
200+
/** @brief Resets the state of the policy. */
201+
virtual void reset() = 0;
202+
};
203+
204+
} // namespace trajectory_cache
205+
} // namespace moveit_ros

0 commit comments

Comments
 (0)