moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Extracts features from the waypoints
and link_name
field in the plan request.
More...
#include <get_cartesian_path_request_features.hpp>
Public Member Functions | |
CartesianWaypointsFeatures (double match_tolerance) | |
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 |
Extracts features from the waypoints
and link_name
field in the plan request.
link_name
is extracted here because it is what the waypoints are stated with reference to. Additionally, the waypoints will be restated in the robot's model frame.
NOTE: In accordance with the source message's field descriptions: If link_name is empty, uses move_group.getEndEffectorLink().
Definition at line 183 of file get_cartesian_path_request_features.hpp.
moveit_ros::trajectory_cache::CartesianWaypointsFeatures::CartesianWaypointsFeatures | ( | double | match_tolerance | ) |
Definition at line 272 of file get_cartesian_path_request_features.cpp.
|
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.
[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. |
Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >.
Definition at line 290 of file get_cartesian_path_request_features.cpp.
|
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.
[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. |
Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >.
Definition at line 282 of file get_cartesian_path_request_features.cpp.
|
overridevirtual |
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
These parameters will be used key the cache element.
[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. |
Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >.
Definition at line 298 of file get_cartesian_path_request_features.cpp.
|
overridevirtual |
Gets the name of the features implementation.
Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >.
Definition at line 277 of file get_cartesian_path_request_features.cpp.