24#include <warehouse_ros/message_collection.h>
26#include <moveit_msgs/srv/get_cartesian_path.hpp>
32namespace trajectory_cache
45 std::string
getName()
const override;
48 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
52 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
57 const moveit_msgs::srv::GetCartesianPath::Request& source,
61 const std::string name_;
78 std::string
getName()
const override;
81 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
85 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
90 const moveit_msgs::srv::GetCartesianPath::Request& source,
95 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
98 const std::string name_;
99 const double match_tolerance_;
119 std::string
getName()
const override;
122 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
126 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
131 const moveit_msgs::srv::GetCartesianPath::Request& source,
135 const std::string name_;
152 std::string
getName()
const override;
155 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
159 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
164 const moveit_msgs::srv::GetCartesianPath::Request& source,
168 const std::string name_;
188 std::string
getName()
const override;
191 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
195 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
200 const moveit_msgs::srv::GetCartesianPath::Request& source,
205 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
208 const std::string name_;
209 const double match_tolerance_;
223 std::string
getName()
const override;
226 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
230 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
235 const moveit_msgs::srv::GetCartesianPath::Request& source,
240 warehouse_ros::Query& query,
const moveit_msgs::srv::GetCartesianPath::Request& source,
243 const std::string name_;
244 const double match_tolerance_;
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Client class to conveniently use the ROS interfaces provided by the move_group node.
Extracts max velocity and acceleration scaling, and cartesian speed limits from the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
CartesianMaxSpeedAndAccelerationFeatures()
std::string getName() const override
Gets the name of the features implementation.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
Extracts max step and jump thresholds from the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
std::string getName() const override
Gets the name of the features implementation.
CartesianMaxStepAndJumpThresholdFeatures()
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
Extracts features from the path_constraints field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
std::string getName() const override
Gets the name of the features implementation.
Extracts details of the joint state from the start_state field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
std::string getName() const override
Gets the name of the features implementation.
Extracts features from the waypoints and link_name field in the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
std::string getName() const override
Gets the name of the features implementation.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
Extracts group name and frame ID from the plan request.
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const moveit_msgs::srv::GetCartesianPath::Request &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const moveit_msgs::srv::GetCartesianPath::Request &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.
CartesianWorkspaceFeatures()
std::string getName() const override
Gets the name of the features implementation.
Abstract template class for extracting features from some FeatureSourceT.