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

Extracts max velocity and acceleration scaling, and cartesian speed limits from the plan request. More...

#include <get_cartesian_path_request_features.hpp>

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

Public Member Functions

 CartesianMaxSpeedAndAccelerationFeatures ()
 
std::string getName () const override
 Gets the name of the features implementation.
 
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.
 
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.
 
- Public Member Functions inherited from moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >
virtual ~FeaturesInterface ()=default
 

Detailed Description

Extracts max velocity and acceleration scaling, and cartesian speed limits from the plan request.

These features will be extracted as less-than-or-equal features.

NOTE: In accordance with the source message's field descriptions: If the max scaling factors are outside the range of (0, 1], they will be set to 1. If max_cartesian_speed is <= 0, it will be ignored instead.

Definition at line 113 of file get_cartesian_path_request_features.hpp.

Constructor & Destructor Documentation

◆ CartesianMaxSpeedAndAccelerationFeatures()

moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures::CartesianMaxSpeedAndAccelerationFeatures ( )

Definition at line 130 of file get_cartesian_path_request_features.cpp.

Member Function Documentation

◆ appendFeaturesAsExactFetchQuery()

MoveItErrorCode moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures::appendFeaturesAsExactFetchQuery ( warehouse_ros::Query &  query,
const moveit_msgs::srv::GetCartesianPath::Request &  source,
const moveit::planning_interface::MoveGroupInterface move_group,
double  exact_match_precision 
) const
overridevirtual

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
[in,out]query.The query to add features to.
[in]source.A FeatureSourceT to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]exact_match_precision.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.

Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >.

Definition at line 147 of file get_cartesian_path_request_features.cpp.

Here is the caller graph for this function:

◆ appendFeaturesAsFuzzyFetchQuery()

MoveItErrorCode moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures::appendFeaturesAsFuzzyFetchQuery ( warehouse_ros::Query &  query,
const moveit_msgs::srv::GetCartesianPath::Request &  source,
const moveit::planning_interface::MoveGroupInterface move_group,
double  exact_match_precision 
) const
overridevirtual

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
[in,out]query.The query to add features to.
[in]source.A FeatureSourceT to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]exact_match_precision.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.

Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >.

Definition at line 140 of file get_cartesian_path_request_features.cpp.

Here is the call graph for this function:

◆ appendFeaturesAsInsertMetadata()

MoveItErrorCode moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures::appendFeaturesAsInsertMetadata ( warehouse_ros::Metadata &  metadata,
const moveit_msgs::srv::GetCartesianPath::Request &  source,
const moveit::planning_interface::MoveGroupInterface move_group 
) const
overridevirtual

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

These parameters will be used key the cache element.

Parameters
[in,out]metadata.The metadata to add features to.
[in]source.A FeatureSourceT to extract features from.
[in]move_group.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.

Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >.

Definition at line 178 of file get_cartesian_path_request_features.cpp.

◆ getName()

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

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