Program Listing for File motion_plan_request_features.hpp

Return to documentation for file (include/moveit/trajectory_cache/features/motion_plan_request_features.hpp)

// Copyright 2024 Intrinsic Innovation LLC.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include <warehouse_ros/message_collection.h>
#include <moveit/move_group_interface/move_group_interface.hpp>
#include <moveit_msgs/msg/robot_trajectory.hpp>
#include <moveit_msgs/msg/motion_plan_request.hpp>

#include <moveit/trajectory_cache/features/features_interface.hpp>

namespace moveit_ros
{
namespace trajectory_cache
{

// "Start" features. ===============================================================================

class WorkspaceFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
{
public:
  WorkspaceFeatures();

  std::string getName() const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
                                 const moveit::planning_interface::MoveGroupInterface& move_group) const override;

private:
  const std::string name_;
};

class StartStateJointStateFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
{
public:
  StartStateJointStateFeatures(double match_tolerance);

  std::string getName() const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
                                 const moveit::planning_interface::MoveGroupInterface& move_group) const override;

private:
  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
      warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
      const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;

  const std::string name_;
  const double match_tolerance_;
};

// "Goal" features. ================================================================================

class MaxSpeedAndAccelerationFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
{
public:
  MaxSpeedAndAccelerationFeatures();

  std::string getName() const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
                                 const moveit::planning_interface::MoveGroupInterface& move_group) const override;

private:
  const std::string name_;
};

class GoalConstraintsFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
{
public:
  GoalConstraintsFeatures(double match_tolerance);

  std::string getName() const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
                                 const moveit::planning_interface::MoveGroupInterface& move_group) const override;

private:
  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
      warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
      const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;

  const std::string name_;
  const double match_tolerance_;
};

class PathConstraintsFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
{
public:
  PathConstraintsFeatures(double match_tolerance);

  std::string getName() const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
                                 const moveit::planning_interface::MoveGroupInterface& move_group) const override;

private:
  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
      warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
      const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;

  const std::string name_;
  const double match_tolerance_;
};

class TrajectoryConstraintsFeatures final : public FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>
{
public:
  TrajectoryConstraintsFeatures(double match_tolerance);

  std::string getName() const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
                                  const moveit::planning_interface::MoveGroupInterface& move_group,
                                  double exact_match_precision) const override;

  moveit::core::MoveItErrorCode
  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const moveit_msgs::msg::MotionPlanRequest& source,
                                 const moveit::planning_interface::MoveGroupInterface& move_group) const override;

private:
  moveit::core::MoveItErrorCode appendFeaturesAsFetchQueryWithTolerance(
      warehouse_ros::Query& query, const moveit_msgs::msg::MotionPlanRequest& source,
      const moveit::planning_interface::MoveGroupInterface& move_group, double match_tolerance) const;

  const std::string name_;
  const double match_tolerance_;
};

}  // namespace trajectory_cache
}  // namespace moveit_ros