diff --git a/nexus_motion_planner/CMakeLists.txt b/nexus_motion_planner/CMakeLists.txt index 2ed33c7..ca94c1e 100644 --- a/nexus_motion_planner/CMakeLists.txt +++ b/nexus_motion_planner/CMakeLists.txt @@ -17,6 +17,7 @@ find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) find_package(trajectory_msgs REQUIRED) find_package(warehouse_ros REQUIRED) +find_package(warehouse_ros_sqlite REQUIRED) include_directories(include) @@ -28,6 +29,7 @@ set (motion_planner_server_dependencies rclcpp_action rclcpp_lifecycle warehouse_ros + warehouse_ros_sqlite tf2 tf2_ros ) @@ -41,12 +43,17 @@ set (test_request_dependencies ) #=============================================================================== -set(LIBRARY_NAME motion_planner_server_core) +set(MOTION_PLAN_CACHE_LIBRARY_NAME motion_planner_server_core) set(EXECUTABLE_NAME motion_planner_server) +# Motion plan cache library +add_library(${MOTION_PLAN_CACHE_LIBRARY_NAME} src/motion_plan_cache.cpp) +ament_target_dependencies(${MOTION_PLAN_CACHE_LIBRARY_NAME} ${motion_planner_server_dependencies}) + # Server executable add_executable(${EXECUTABLE_NAME} src/main.cpp src/motion_planner_server.cpp) ament_target_dependencies(${EXECUTABLE_NAME} ${motion_planner_server_dependencies}) +target_link_libraries(${EXECUTABLE_NAME} ${MOTION_PLAN_CACHE_LIBRARY_NAME}) # Test executable add_executable(test_request src/test_request.cpp) diff --git a/nexus_motion_planner/src/main.cpp b/nexus_motion_planner/src/main.cpp index 655af9f..c1d7353 100644 --- a/nexus_motion_planner/src/main.cpp +++ b/nexus_motion_planner/src/main.cpp @@ -27,7 +27,7 @@ int main(int argc, char** argv) setvbuf(stdout, NULL, _IONBF, BUFSIZ); rclcpp::init(argc, argv); - auto node = std::make_shared(); + auto node = std::make_shared(); rclcpp::spin(node->get_node_base_interface()); rclcpp::shutdown(); return 0; diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp new file mode 100644 index 0000000..b2e8096 --- /dev/null +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -0,0 +1,1601 @@ +// Copyright 2022 Johnson & Johnson +// +// 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. + +#include +#include + +#include "moveit/robot_state/conversions.h" +#include "moveit/robot_state/robot_state.h" +#include "warehouse_ros/database_loader.h" + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/logging.hpp" +#include "motion_plan_cache.hpp" + +namespace nexus { +namespace motion_planner { + +using warehouse_ros::MessageWithMetadata; +using warehouse_ros::Metadata; +using warehouse_ros::Query; + +// Utils ======================================================================= + +// Append a range inclusive query with some tolerance about some center value. +void query_append_range_inclusive_with_tolerance( + Query& query, const std::string& name, double center, double tolerance) +{ + query.appendRangeInclusive( + name, center - tolerance / 2, center + tolerance / 2); +} + +// Sort constraint components by joint or link name. +void sort_constraints( + std::vector& joint_constraints, + std::vector& position_constraints, + std::vector& orientation_constraints) +{ + std::sort( + joint_constraints.begin(), joint_constraints.end(), + []( + const moveit_msgs::msg::JointConstraint& l, + const moveit_msgs::msg::JointConstraint& r) + { + return l.joint_name < r.joint_name; + }); + + std::sort( + position_constraints.begin(), position_constraints.end(), + []( + const moveit_msgs::msg::PositionConstraint& l, + const moveit_msgs::msg::PositionConstraint& r) + { + return l.link_name < r.link_name; + }); + + std::sort( + orientation_constraints.begin(), orientation_constraints.end(), + []( + const moveit_msgs::msg::OrientationConstraint& l, + const moveit_msgs::msg::OrientationConstraint& r) + { + return l.link_name < r.link_name; + }); +} + +// Motion Plan Cache =========================================================== + +MotionPlanCache::MotionPlanCache(const rclcpp::Node::SharedPtr& node) +: node_(node) +{ + tf_buffer_ = + std::make_unique(node_->get_clock()); + tf_listener_ = + std::make_shared(*tf_buffer_); + + // If the `warehouse_plugin` parameter isn't set, defaults to warehouse_ros' + // default. + warehouse_ros::DatabaseLoader loader(node_); + db_ = loader.loadDatabase(); +} + +bool MotionPlanCache::init( + const std::string& db_path, uint32_t db_port, double exact_match_precision) +{ + RCLCPP_INFO( + node_->get_logger(), + "Opening motion plan cache database at: %s (Port: %d, Precision: %f)", + db_path.c_str(), db_port, exact_match_precision); + + exact_match_precision_ = exact_match_precision; + db_->setParams(db_path, db_port); + return db_->connect(); +} + +// ============================================================================= +// MOTION PLAN CACHING +// ============================================================================= +// MOTION PLAN CACHING: TOP LEVEL OPS +std::vector::ConstPtr> +MotionPlanCache::fetch_all_matching_plans( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double start_tolerance, double goal_tolerance, bool metadata_only, + const std::string& sort_by) +{ + auto coll = db_->openCollection( + "move_group_plan_cache", move_group_namespace); + + Query::Ptr query = coll.createQuery(); + + bool start_ok = this->extract_and_append_plan_start_to_query( + *query, move_group, plan_request, start_tolerance); + bool goal_ok = this->extract_and_append_plan_goal_to_query( + *query, move_group, plan_request, goal_tolerance); + + if (!start_ok || !goal_ok) + { + RCLCPP_ERROR(node_->get_logger(), "Could not construct plan query."); + return {}; + } + + return coll.queryList(query, metadata_only, sort_by, true); +} + +MessageWithMetadata::ConstPtr +MotionPlanCache::fetch_best_matching_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double start_tolerance, double goal_tolerance, bool metadata_only, + const std::string& sort_by) +{ + // First find all matching, but metadata only. + // Then use the ID metadata of the best plan to pull the actual message. + auto matching_plans = this->fetch_all_matching_plans( + move_group, move_group_namespace, + plan_request, start_tolerance, goal_tolerance, true, sort_by); + + if (matching_plans.empty()) + { + RCLCPP_INFO(node_->get_logger(), "No matching plans found."); + return nullptr; + } + + auto coll = db_->openCollection( + "move_group_plan_cache", move_group_namespace); + + // Best plan is at first index, since the lookup query was sorted by + // execution_time. + int best_plan_id = matching_plans.at(0)->lookupInt("id"); + Query::Ptr best_query = coll.createQuery(); + best_query->append("id", best_plan_id); + + return coll.findOne(best_query, metadata_only); +} + +bool +MotionPlanCache::put_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + const moveit_msgs::msg::RobotTrajectory& plan, + double execution_time_s, double planning_time_s, bool delete_worse_plans) +{ + // Check pre-conditions + if (!plan.multi_dof_joint_trajectory.points.empty()) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping plan insert: Multi-DOF trajectory plans are not supported."); + return false; + } + if (plan_request.workspace_parameters.header.frame_id.empty() || + plan.joint_trajectory.header.frame_id.empty()) + { + RCLCPP_ERROR( + node_->get_logger(), "Skipping plan insert: Frame IDs cannot be empty."); + return false; + } + if (plan_request.workspace_parameters.header.frame_id != + plan.joint_trajectory.header.frame_id) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping plan insert: " + "Plan request frame (%s) does not match plan frame (%s).", + plan_request.workspace_parameters.header.frame_id.c_str(), + plan.joint_trajectory.header.frame_id.c_str()); + return false; + } + + auto coll = db_->openCollection( + "move_group_plan_cache", move_group_namespace); + + // Pull out "exact" matching plans in cache. + Query::Ptr exact_query = coll.createQuery(); + + bool start_query_ok = this->extract_and_append_plan_start_to_query( + *exact_query, move_group, plan_request, 0); + bool goal_query_ok = this->extract_and_append_plan_goal_to_query( + *exact_query, move_group, plan_request, 0); + + if (!start_query_ok || !goal_query_ok) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping plan insert: Could not construct lookup query."); + return false; + } + + auto exact_matches = coll.queryList( + exact_query, /* metadata_only */ true, /* sort_by */ "execution_time_s"); + + double best_execution_time = std::numeric_limits::infinity(); + if (!exact_matches.empty()) + { + best_execution_time = exact_matches.at(0)->lookupDouble("execution_time_s"); + + if (delete_worse_plans) + { + for (auto& match : exact_matches) + { + double match_execution_time_s = match->lookupDouble("execution_time_s"); + if (execution_time_s < match_execution_time_s) + { + int delete_id = match->lookupInt("id"); + RCLCPP_INFO( + node_->get_logger(), + "Overwriting plan (id: %d): " + "execution_time (%es) > new plan's execution_time (%es)", + delete_id, match_execution_time_s, execution_time_s); + + Query::Ptr delete_query = coll.createQuery(); + delete_query->append("id", delete_id); + coll.removeMessages(delete_query); + } + } + } + } + + // Insert if candidate is best seen. + if (execution_time_s < best_execution_time) + { + Metadata::Ptr insert_metadata = coll.createMetadata(); + + bool start_meta_ok = this->extract_and_append_plan_start_to_metadata( + *insert_metadata, move_group, plan_request); + bool goal_meta_ok = this->extract_and_append_plan_goal_to_metadata( + *insert_metadata, move_group, plan_request); + insert_metadata->append("execution_time_s", execution_time_s); + insert_metadata->append("planning_time_s", planning_time_s); + + if (!start_meta_ok || !goal_meta_ok) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping plan insert: Could not construct insert metadata."); + return false; + } + + RCLCPP_INFO( + node_->get_logger(), + "Inserting plan: New plan execution_time (%es) " + "is better than best plan's execution_time (%es)", + execution_time_s, best_execution_time); + + coll.insert(plan, insert_metadata); + return true; + } + + RCLCPP_INFO( + node_->get_logger(), + "Skipping plan insert: New plan execution_time (%es) " + "is worse than best plan's execution_time (%es)", + execution_time_s, best_execution_time); + return false; +} + +// MOTION PLAN CACHING: QUERY CONSTRUCTION +bool +MotionPlanCache::extract_and_append_plan_start_to_query( + Query& query, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double match_tolerance) +{ + match_tolerance += exact_match_precision_; + + // Make ignored members explicit + if (!plan_request.start_state.multi_dof_joint_state.joint_names.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.multi_dof_joint_states: Not supported."); + } + if (!plan_request.start_state.attached_collision_objects.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.attached_collision_objects: Not supported."); + } + + // auto original = *query; // Copy not supported. + + query.append("group_name", plan_request.group_name); + + // Workspace params + // Match anything within our specified workspace limits. + query.append( + "workspace_parameters.header.frame_id", + plan_request.workspace_parameters.header.frame_id); + query.appendGTE( + "workspace_parameters.min_corner.x", + plan_request.workspace_parameters.min_corner.x); + query.appendGTE( + "workspace_parameters.min_corner.y", + plan_request.workspace_parameters.min_corner.y); + query.appendGTE( + "workspace_parameters.min_corner.z", + plan_request.workspace_parameters.min_corner.z); + query.appendLTE( + "workspace_parameters.max_corner.x", + plan_request.workspace_parameters.max_corner.x); + query.appendLTE( + "workspace_parameters.max_corner.y", + plan_request.workspace_parameters.max_corner.y); + query.appendLTE( + "workspace_parameters.max_corner.z", + plan_request.workspace_parameters.max_corner.z); + + // Joint state + // Only accounts for joint_state position. Ignores velocity and effort. + if (plan_request.start_state.is_diff) + { + // If plan request states that the start_state is_diff, then we need to get + // the current state from the move_group. + + // NOTE: methyldragon - + // I think if is_diff is on, the joint states will not be populated in all + // of our motion plan requests? If this isn't the case we might need to + // apply the joint states as offsets as well. + // + // TODO: Since MoveIt also potentially does another getCurrentState() call + // when planning, there is a chance that the current state in the cache + // differs from the state used in MoveIt's plan. + // + // When upstreaming this class to MoveIt, this issue should go away once + // the class is used within the move group's Plan call. + moveit::core::RobotStatePtr current_state = move_group.getCurrentState(); + if (!current_state) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping start query append: Could not get robot state."); + // *query = original; // Undo our changes. (Can't. Copy not supported.) + return false; + } + + moveit_msgs::msg::RobotState current_state_msg; + robotStateToRobotStateMsg(*current_state, current_state_msg); + + for (size_t i = 0; i < current_state_msg.joint_state.name.size(); i++) + { + query.append( + "start_state.joint_state.name_" + std::to_string(i), + current_state_msg.joint_state.name.at(i)); + query_append_range_inclusive_with_tolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + current_state_msg.joint_state.position.at(i), match_tolerance); + } + } + else + { + for ( + size_t i = 0; i < plan_request.start_state.joint_state.name.size(); i++ + ) + { + query.append( + "start_state.joint_state.name_" + std::to_string(i), + plan_request.start_state.joint_state.name.at(i)); + query_append_range_inclusive_with_tolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + plan_request.start_state.joint_state.position.at(i), match_tolerance); + } + } + return true; +} + +bool +MotionPlanCache::extract_and_append_plan_goal_to_query( + Query& query, + const moveit::planning_interface::MoveGroupInterface& /* move_group */, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double match_tolerance) +{ + match_tolerance += exact_match_precision_; + + // Make ignored members explicit + bool emit_position_constraint_warning = false; + for (auto& constraint : plan_request.goal_constraints) + { + for (auto& position_constraint : constraint.position_constraints) + { + if (!position_constraint.constraint_region.primitives.empty()) + { + emit_position_constraint_warning = true; + break; + } + } + if (emit_position_constraint_warning) + { + break; + } + } + if (emit_position_constraint_warning) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring goal_constraints.position_constraints.constraint_region: " + "Not supported."); + } + + // auto original = *query; // Copy not supported. + + query_append_range_inclusive_with_tolerance( + query, "max_velocity_scaling_factor", + plan_request.max_velocity_scaling_factor, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, "max_acceleration_scaling_factor", + plan_request.max_acceleration_scaling_factor, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, "max_cartesian_speed", + plan_request.max_cartesian_speed, match_tolerance); + + // Extract constraints (so we don't have cardinality on goal_constraint idx.) + std::vector joint_constraints; + std::vector position_constraints; + std::vector orientation_constraints; + for (auto& constraint : plan_request.goal_constraints) + { + for (auto& joint_constraint : constraint.joint_constraints) + { + joint_constraints.push_back(joint_constraint); + } + for (auto& position_constraint : constraint.position_constraints) + { + position_constraints.push_back(position_constraint); + } + for (auto& orientation_constraint : constraint.orientation_constraints) + { + orientation_constraints.push_back(orientation_constraint); + } + + // Also sort for even less cardinality. + sort_constraints( + joint_constraints, position_constraints, orientation_constraints); + } + + // Joint constraints + size_t joint_idx = 0; + for (auto& constraint : joint_constraints) + { + std::string meta_name = + "goal_constraints.joint_constraints_" + std::to_string(joint_idx++); + + query.append(meta_name + ".joint_name", constraint.joint_name); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".position", constraint.position, match_tolerance); + query.appendGTE(meta_name + ".tolerance_above", constraint.tolerance_above); + query.appendLTE(meta_name + ".tolerance_below", constraint.tolerance_below); + } + + // Position constraints + // All offsets will be "frozen" and computed wrt. the workspace frame + // instead. + if (!position_constraints.empty()) + { + query.append( + "goal_constraints.position_constraints.header.frame_id", + plan_request.workspace_parameters.header.frame_id); + + size_t pos_idx = 0; + for (auto& constraint : position_constraints) + { + std::string meta_name = + "goal_constraints.position_constraints_" + std::to_string(pos_idx++); + + // Compute offsets wrt. to workspace frame. + double x_offset = 0; + double y_offset = 0; + double z_offset = 0; + + if (plan_request.workspace_parameters.header.frame_id != + constraint.header.frame_id) + { + try + { + auto transform = tf_buffer_->lookupTransform( + constraint.header.frame_id, + plan_request.workspace_parameters.header.frame_id, + tf2::TimePointZero); + + x_offset = transform.transform.translation.x; + y_offset = transform.transform.translation.y; + z_offset = transform.transform.translation.z; + } + catch (tf2::TransformException& ex) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping goal query append: " + "Could not get goal transform for translation %s to %s: %s", + plan_request.workspace_parameters.header.frame_id.c_str(), + constraint.header.frame_id.c_str(), + ex.what()); + + // (Can't. Copy not supported.) + // *query = original; // Undo our changes. + return false; + } + } + + query.append(meta_name + ".link_name", constraint.link_name); + + query_append_range_inclusive_with_tolerance( + query, meta_name + ".target_point_offset.x", + x_offset + constraint.target_point_offset.x, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".target_point_offset.y", + y_offset + constraint.target_point_offset.y, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".target_point_offset.z", + z_offset + constraint.target_point_offset.z, match_tolerance); + } + } + + // Orientation constraints + // All offsets will be "frozen" and computed wrt. the workspace frame + // instead. + if (!orientation_constraints.empty()) + { + query.append( + "goal_constraints.orientation_constraints.header.frame_id", + plan_request.workspace_parameters.header.frame_id); + + size_t ori_idx = 0; + for (auto& constraint : orientation_constraints) + { + std::string meta_name = + "goal_constraints.orientation_constraints_" + std::to_string(ori_idx++); + + // Compute offsets wrt. to workspace frame. + geometry_msgs::msg::Quaternion quat_offset; + quat_offset.x = 0; + quat_offset.y = 0; + quat_offset.z = 0; + quat_offset.w = 1; + + if (plan_request.workspace_parameters.header.frame_id != + constraint.header.frame_id) + { + try + { + auto transform = tf_buffer_->lookupTransform( + constraint.header.frame_id, + plan_request.workspace_parameters.header.frame_id, + tf2::TimePointZero); + + quat_offset = transform.transform.rotation; + } + catch (tf2::TransformException& ex) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping goal query append: " + "Could not get goal transform for orientation %s to %s: %s", + plan_request.workspace_parameters.header.frame_id.c_str(), + constraint.header.frame_id.c_str(), + ex.what()); + + // (Can't. Copy not supported.) + // *query = original; // Undo our changes. + return false; + } + } + + query.append(meta_name + ".link_name", constraint.link_name); + + // Orientation of constraint frame wrt. workspace frame + tf2::Quaternion tf2_quat_frame_offset( + quat_offset.x, quat_offset.y, quat_offset.z, quat_offset.w); + + // Added offset on top of the constraint frame's orientation stated in + // the constraint. + tf2::Quaternion tf2_quat_goal_offset( + constraint.orientation.x, + constraint.orientation.y, + constraint.orientation.z, + constraint.orientation.w); + + tf2_quat_frame_offset.normalize(); + tf2_quat_goal_offset.normalize(); + + auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; + final_quat.normalize(); + + query_append_range_inclusive_with_tolerance( + query, meta_name + ".target_point_offset.x", + final_quat.getX(), match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".target_point_offset.y", + final_quat.getY(), match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".target_point_offset.z", + final_quat.getZ(), match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".target_point_offset.w", + final_quat.getW(), match_tolerance); + } + } + + return true; +} + +// MOTION PLAN CACHING: METADATA CONSTRUCTION +bool +MotionPlanCache::extract_and_append_plan_start_to_metadata( + Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::msg::MotionPlanRequest& plan_request) +{ + // Make ignored members explicit + if (!plan_request.start_state.multi_dof_joint_state.joint_names.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.multi_dof_joint_states: Not supported."); + } + if (!plan_request.start_state.attached_collision_objects.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.attached_collision_objects: Not supported."); + } + + // auto original = *metadata; // Copy not supported. + + metadata.append("group_name", plan_request.group_name); + + // Workspace params + metadata.append( + "workspace_parameters.header.frame_id", + plan_request.workspace_parameters.header.frame_id); + metadata.append( + "workspace_parameters.min_corner.x", + plan_request.workspace_parameters.min_corner.x); + metadata.append( + "workspace_parameters.min_corner.y", + plan_request.workspace_parameters.min_corner.y); + metadata.append( + "workspace_parameters.min_corner.z", + plan_request.workspace_parameters.min_corner.z); + metadata.append( + "workspace_parameters.max_corner.x", + plan_request.workspace_parameters.max_corner.x); + metadata.append( + "workspace_parameters.max_corner.y", + plan_request.workspace_parameters.max_corner.y); + metadata.append( + "workspace_parameters.max_corner.z", + plan_request.workspace_parameters.max_corner.z); + + // Joint state + // Only accounts for joint_state position. Ignores velocity and effort. + if (plan_request.start_state.is_diff) + { + // If plan request states that the start_state is_diff, then we need to get + // the current state from the move_group. + + // NOTE: methyldragon - + // I think if is_diff is on, the joint states will not be populated in all + // of our motion plan requests? If this isn't the case we might need to + // apply the joint states as offsets as well. + // + // TODO: Since MoveIt also potentially does another getCurrentState() call + // when planning, there is a chance that the current state in the cache + // differs from the state used in MoveIt's plan. + // + // When upstreaming this class to MoveIt, this issue should go away once + // the class is used within the move group's Plan call. + moveit::core::RobotStatePtr current_state = move_group.getCurrentState(); + if (!current_state) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping start metadata append: Could not get robot state."); + // *metadata = original; // Undo our changes. // Copy not supported + return false; + } + + moveit_msgs::msg::RobotState current_state_msg; + robotStateToRobotStateMsg(*current_state, current_state_msg); + + for (size_t i = 0; i < current_state_msg.joint_state.name.size(); i++) + { + metadata.append( + "start_state.joint_state.name_" + std::to_string(i), + current_state_msg.joint_state.name.at(i)); + metadata.append( + "start_state.joint_state.position_" + std::to_string(i), + current_state_msg.joint_state.position.at(i)); + } + } + else + { + for ( + size_t i = 0; i < plan_request.start_state.joint_state.name.size(); i++ + ) + { + metadata.append( + "start_state.joint_state.name_" + std::to_string(i), + plan_request.start_state.joint_state.name.at(i)); + metadata.append( + "start_state.joint_state.position_" + std::to_string(i), + plan_request.start_state.joint_state.position.at(i)); + } + } + + return true; +} + +bool +MotionPlanCache::extract_and_append_plan_goal_to_metadata( + Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& /* move_group */, + const moveit_msgs::msg::MotionPlanRequest& plan_request) +{ + // Make ignored members explicit + bool emit_position_constraint_warning = false; + for (auto& constraint : plan_request.goal_constraints) + { + for (auto& position_constraint : constraint.position_constraints) + { + if (!position_constraint.constraint_region.primitives.empty()) + { + emit_position_constraint_warning = true; + break; + } + } + if (emit_position_constraint_warning) + { + break; + } + } + if (emit_position_constraint_warning) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring goal_constraints.position_constraints.constraint_region: " + "Not supported."); + } + + // auto original = *metadata; // Copy not supported. + + metadata.append("max_velocity_scaling_factor", + plan_request.max_velocity_scaling_factor); + metadata.append("max_acceleration_scaling_factor", + plan_request.max_acceleration_scaling_factor); + metadata.append("max_cartesian_speed", plan_request.max_cartesian_speed); + + // Extract constraints (so we don't have cardinality on goal_constraint idx.) + std::vector joint_constraints; + std::vector position_constraints; + std::vector orientation_constraints; + for (auto& constraint : plan_request.goal_constraints) + { + for (auto& joint_constraint : constraint.joint_constraints) + { + joint_constraints.push_back(joint_constraint); + } + for (auto& position_constraint : constraint.position_constraints) + { + position_constraints.push_back(position_constraint); + } + for (auto& orientation_constraint : constraint.orientation_constraints) + { + orientation_constraints.push_back(orientation_constraint); + } + + // Also sort for even less cardinality. + sort_constraints( + joint_constraints, position_constraints, orientation_constraints); + } + + // Joint constraints + size_t joint_idx = 0; + for (auto& constraint : joint_constraints) + { + std::string meta_name = + "goal_constraints.joint_constraints_" + std::to_string(joint_idx++); + + metadata.append(meta_name + ".joint_name", constraint.joint_name); + metadata.append(meta_name + ".position", constraint.position); + metadata.append( + meta_name + ".tolerance_above", constraint.tolerance_above); + metadata.append( + meta_name + ".tolerance_below", constraint.tolerance_below); + } + + // Position constraints + if (!position_constraints.empty()) + { + // All offsets will be "frozen" and computed wrt. the workspace frame + // instead. + metadata.append( + "goal_constraints.position_constraints.header.frame_id", + plan_request.workspace_parameters.header.frame_id); + + size_t position_idx = 0; + for (auto& constraint : position_constraints) + { + std::string meta_name = + "goal_constraints.position_constraints_" + + std::to_string(position_idx++); + + // Compute offsets wrt. to workspace frame. + double x_offset = 0; + double y_offset = 0; + double z_offset = 0; + + if (plan_request.workspace_parameters.header.frame_id != + constraint.header.frame_id) + { + try + { + auto transform = tf_buffer_->lookupTransform( + constraint.header.frame_id, + plan_request.workspace_parameters.header.frame_id, + tf2::TimePointZero); + + x_offset = transform.transform.translation.x; + y_offset = transform.transform.translation.y; + z_offset = transform.transform.translation.z; + } + catch (tf2::TransformException& ex) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping goal metadata append: " + "Could not get goal transform for translation %s to %s: %s", + plan_request.workspace_parameters.header.frame_id.c_str(), + constraint.header.frame_id.c_str(), + ex.what()); + + // (Can't. Copy not supported.) + // *metadata = original; // Undo our changes. + return false; + } + } + + metadata.append(meta_name + ".link_name", constraint.link_name); + + metadata.append( + meta_name + ".target_point_offset.x", + x_offset + constraint.target_point_offset.x); + metadata.append( + meta_name + ".target_point_offset.y", + y_offset + constraint.target_point_offset.y); + metadata.append( + meta_name + ".target_point_offset.z", + z_offset + constraint.target_point_offset.z); + } + } + + // Orientation constraints + if (!orientation_constraints.empty()) + { + // All offsets will be "frozen" and computed wrt. the workspace frame + // instead. + metadata.append( + "goal_constraints.orientation_constraints.header.frame_id", + plan_request.workspace_parameters.header.frame_id); + + size_t ori_idx = 0; + for (auto& constraint : orientation_constraints) + { + std::string meta_name = + "goal_constraints.orientation_constraints_" + std::to_string(ori_idx++); + + // Compute offsets wrt. to workspace frame. + geometry_msgs::msg::Quaternion quat_offset; + quat_offset.x = 0; + quat_offset.y = 0; + quat_offset.z = 0; + quat_offset.w = 1; + + if (plan_request.workspace_parameters.header.frame_id != + constraint.header.frame_id) + { + try + { + auto transform = tf_buffer_->lookupTransform( + constraint.header.frame_id, + plan_request.workspace_parameters.header.frame_id, + tf2::TimePointZero); + + quat_offset = transform.transform.rotation; + } + catch (tf2::TransformException& ex) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping goal metadata append: " + "Could not get goal transform for orientation %s to %s: %s", + plan_request.workspace_parameters.header.frame_id.c_str(), + constraint.header.frame_id.c_str(), + ex.what()); + + // (Can't. Copy not supported.) + // *metadata = original; // Undo our changes. + return false; + } + } + + metadata.append(meta_name + ".link_name", constraint.link_name); + + // Orientation of constraint frame wrt. workspace frame + tf2::Quaternion tf2_quat_frame_offset( + quat_offset.x, quat_offset.y, quat_offset.z, quat_offset.w); + + // Added offset on top of the constraint frame's orientation stated in + // the constraint. + tf2::Quaternion tf2_quat_goal_offset( + constraint.orientation.x, + constraint.orientation.y, + constraint.orientation.z, + constraint.orientation.w); + + tf2_quat_frame_offset.normalize(); + tf2_quat_goal_offset.normalize(); + + auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; + final_quat.normalize(); + + metadata.append(meta_name + ".target_point_offset.x", + final_quat.getX()); + metadata.append(meta_name + ".target_point_offset.y", + final_quat.getY()); + metadata.append(meta_name + ".target_point_offset.z", + final_quat.getZ()); + metadata.append(meta_name + ".target_point_offset.w", + final_quat.getW()); + } + } + + return true; +} + +// ============================================================================= +// CARTESIAN PLAN CACHING +// ============================================================================= +// CARTESIAN PLAN CACHING: TOP LEVEL OPS +moveit_msgs::srv::GetCartesianPath::Request +MotionPlanCache::construct_get_cartesian_plan_request( + moveit::planning_interface::MoveGroupInterface& move_group, + const std::vector& waypoints, + double step, double jump_threshold, bool avoid_collisions) +{ + moveit_msgs::srv::GetCartesianPath::Request out; + + // Some of these parameters need us to pull PRIVATE values out of the + // move_group elsewhere... Yes, it is very cursed and I hate it. + // Fixing it requires fixing it in MoveIt. + moveit_msgs::msg::MotionPlanRequest tmp; + move_group.constructMotionPlanRequest(tmp); + + out.start_state = std::move(tmp.start_state); + out.group_name = std::move(tmp.group_name); + out.max_velocity_scaling_factor = tmp.max_velocity_scaling_factor; + out.max_acceleration_scaling_factor = tmp.max_acceleration_scaling_factor; + + out.header.frame_id = move_group.getPoseReferenceFrame(); + out.waypoints = waypoints; + out.max_step = step; + out.jump_threshold = jump_threshold; + out.path_constraints = moveit_msgs::msg::Constraints(); + out.avoid_collisions = avoid_collisions; + out.link_name = move_group.getEndEffectorLink(); + + // We were already cursed before, now we are double cursed... + // move_group.getNodeHandle() is UNIMPLEMENTED upstream. + out.header.stamp = node_->now(); + + return out; +} + +std::vector::ConstPtr> +MotionPlanCache::fetch_all_matching_cartesian_plans( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double min_fraction, + double start_tolerance, double goal_tolerance, bool metadata_only, + const std::string& sort_by) +{ + auto coll = db_->openCollection( + "move_group_cartesian_plan_cache", move_group_namespace); + + Query::Ptr query = coll.createQuery(); + + bool start_ok = this->extract_and_append_cartesian_plan_start_to_query( + *query, move_group, plan_request, start_tolerance); + bool goal_ok = this->extract_and_append_cartesian_plan_goal_to_query( + *query, move_group, plan_request, goal_tolerance); + + if (!start_ok || !goal_ok) + { + RCLCPP_ERROR( + node_->get_logger(), "Could not construct cartesian plan query."); + return {}; + } + + query->appendGTE("fraction", min_fraction); + return coll.queryList(query, metadata_only, sort_by, true); +} + +MessageWithMetadata::ConstPtr +MotionPlanCache::fetch_best_matching_cartesian_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double min_fraction, + double start_tolerance, double goal_tolerance, bool metadata_only, + const std::string& sort_by) +{ + // First find all matching, but metadata only. + // Then use the ID metadata of the best plan to pull the actual message. + auto matching_plans = this->fetch_all_matching_cartesian_plans( + move_group, move_group_namespace, + plan_request, min_fraction, + start_tolerance, goal_tolerance, true, sort_by); + + if (matching_plans.empty()) + { + RCLCPP_INFO(node_->get_logger(), "No matching cartesian plans found."); + return nullptr; + } + + auto coll = db_->openCollection( + "move_group_plan_cache", move_group_namespace); + + // Best plan is at first index, since the lookup query was sorted by + // execution_time. + int best_plan_id = matching_plans.at(0)->lookupInt("id"); + Query::Ptr best_query = coll.createQuery(); + best_query->append("id", best_plan_id); + + return coll.findOne(best_query, metadata_only); +} + +bool +MotionPlanCache::put_cartesian_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + const moveit_msgs::msg::RobotTrajectory& plan, + double execution_time_s, + double planning_time_s, + double fraction, + bool delete_worse_plans) +{ + // Check pre-conditions + if (!plan.multi_dof_joint_trajectory.points.empty()) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping cartesian plan insert: " + "Multi-DOF trajectory plans are not supported."); + return false; + } + if (plan_request.header.frame_id.empty() || + plan.joint_trajectory.header.frame_id.empty()) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping cartesian plan insert: " + "Frame IDs cannot be empty."); + return false; + } + + auto coll = db_->openCollection( + "move_group_cartesian_plan_cache", move_group_namespace); + + // Pull out "exact" matching plans in cache. + Query::Ptr exact_query = coll.createQuery(); + + bool start_query_ok = this->extract_and_append_cartesian_plan_start_to_query( + *exact_query, move_group, plan_request, 0); + bool goal_query_ok = this->extract_and_append_cartesian_plan_goal_to_query( + *exact_query, move_group, plan_request, 0); + exact_query->append("fraction", fraction); + + if (!start_query_ok || !goal_query_ok) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping cartesian plan insert: Could not construct lookup query."); + return false; + } + + auto exact_matches = coll.queryList( + exact_query, /* metadata_only */ true, /* sort_by */ "execution_time_s"); + double best_execution_time = std::numeric_limits::infinity(); + if (!exact_matches.empty()) + { + best_execution_time = exact_matches.at(0)->lookupDouble("execution_time_s"); + + if (delete_worse_plans) + { + for (auto& match : exact_matches) + { + double match_execution_time_s = match->lookupDouble("execution_time_s"); + if (execution_time_s < match_execution_time_s) + { + int delete_id = match->lookupInt("id"); + RCLCPP_INFO( + node_->get_logger(), + "Overwriting cartesian plan (id: %d): " + "execution_time (%es) > new plan's execution_time (%es)", + delete_id, match_execution_time_s, execution_time_s); + + Query::Ptr delete_query = coll.createQuery(); + delete_query->append("id", delete_id); + coll.removeMessages(delete_query); + } + } + } + } + + // Insert if candidate is best seen. + if (execution_time_s < best_execution_time) + { + Metadata::Ptr insert_metadata = coll.createMetadata(); + + bool start_meta_ok = + this->extract_and_append_cartesian_plan_start_to_metadata( + *insert_metadata, move_group, plan_request); + bool goal_meta_ok = + this->extract_and_append_cartesian_plan_goal_to_metadata( + *insert_metadata, move_group, plan_request); + insert_metadata->append("execution_time_s", execution_time_s); + insert_metadata->append("planning_time_s", planning_time_s); + insert_metadata->append("fraction", fraction); + + if (!start_meta_ok || !goal_meta_ok) + { + RCLCPP_ERROR( + node_->get_logger(), + "Skipping cartesian plan insert: Could not construct insert metadata."); + return false; + } + + RCLCPP_INFO( + node_->get_logger(), + "Inserting cartesian plan: New plan execution_time (%es) " + "is better than best plan's execution_time (%es) at fraction (%es)", + execution_time_s, best_execution_time, fraction); + + coll.insert(plan, insert_metadata); + return true; + } + + RCLCPP_INFO( + node_->get_logger(), + "Skipping cartesian plan insert: New plan execution_time (%es) " + "is worse than best plan's execution_time (%es) at fraction (%es)", + execution_time_s, best_execution_time, fraction); + return false; +} + +// // CARTESIAN PLAN CACHING: QUERY CONSTRUCTION +bool +MotionPlanCache::extract_and_append_cartesian_plan_start_to_query( + Query& query, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double match_tolerance) +{ + match_tolerance += exact_match_precision_; + + // Make ignored members explicit + if (!plan_request.start_state.multi_dof_joint_state.joint_names.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.multi_dof_joint_states: Not supported."); + } + if (!plan_request.start_state.attached_collision_objects.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.attached_collision_objects: Not supported."); + } + + // auto original = *metadata; // Copy not supported. + + query.append("group_name", plan_request.group_name); + + // Joint state + // Only accounts for joint_state position. Ignores velocity and effort. + if (plan_request.start_state.is_diff) + { + // If plan request states that the start_state is_diff, then we need to get + // the current state from the move_group. + + // NOTE: methyldragon - + // I think if is_diff is on, the joint states will not be populated in all + // of our motion plan requests? If this isn't the case we might need to + // apply the joint states as offsets as well. + // + // TODO: Since MoveIt also potentially does another getCurrentState() call + // when planning, there is a chance that the current state in the cache + // differs from the state used in MoveIt's plan. + // + // When upstreaming this class to MoveIt, this issue should go away once + // the class is used within the move group's Plan call. + moveit::core::RobotStatePtr current_state = move_group.getCurrentState(); + if (!current_state) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping start metadata append: Could not get robot state."); + // *metadata = original; // Undo our changes. // Copy not supported + return false; + } + + moveit_msgs::msg::RobotState current_state_msg; + robotStateToRobotStateMsg(*current_state, current_state_msg); + + for (size_t i = 0; i < current_state_msg.joint_state.name.size(); i++) + { + query.append( + "start_state.joint_state.name_" + std::to_string(i), + current_state_msg.joint_state.name.at(i)); + query_append_range_inclusive_with_tolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + current_state_msg.joint_state.position.at(i), match_tolerance); + } + } + else + { + for ( + size_t i = 0; i < plan_request.start_state.joint_state.name.size(); i++ + ) + { + query.append( + "start_state.joint_state.name_" + std::to_string(i), + plan_request.start_state.joint_state.name.at(i)); + query_append_range_inclusive_with_tolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + plan_request.start_state.joint_state.position.at(i), match_tolerance); + } + } + + return true; +} + +bool +MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( + Query& query, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double match_tolerance) +{ + match_tolerance += exact_match_precision_; + + // Make ignored members explicit + if (plan_request.path_constraints.joint_constraints.empty() || + plan_request.path_constraints.position_constraints.empty() || + plan_request.path_constraints.orientation_constraints.empty() || + plan_request.path_constraints.visibility_constraints.empty()) + { + RCLCPP_WARN( + node_->get_logger(), "Ignoring path_constraints: Not supported."); + } + if (plan_request.avoid_collisions) + { + RCLCPP_WARN(node_->get_logger(), + "Ignoring avoid_collisions: Not supported."); + } + + // auto original = *metadata; // Copy not supported. + + query_append_range_inclusive_with_tolerance( + query, "max_velocity_scaling_factor", + plan_request.max_velocity_scaling_factor, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, "max_acceleration_scaling_factor", + plan_request.max_acceleration_scaling_factor, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, "max_step", plan_request.max_step, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, "jump_threshold", plan_request.jump_threshold, match_tolerance); + + // Waypoints + // Restating them in terms of the robot model frame (usually base_link) + std::string base_frame = move_group.getRobotModel()->getModelFrame(); + + // Compute offsets. + double x_offset = 0; + double y_offset = 0; + double z_offset = 0; + + geometry_msgs::msg::Quaternion quat_offset; + quat_offset.x = 0; + quat_offset.y = 0; + quat_offset.z = 0; + quat_offset.w = 1; + + if (base_frame != plan_request.header.frame_id) + { + try + { + auto transform = tf_buffer_->lookupTransform( + plan_request.header.frame_id, base_frame, tf2::TimePointZero); + + x_offset = transform.transform.translation.x; + y_offset = transform.transform.translation.y; + z_offset = transform.transform.translation.z; + quat_offset = transform.transform.rotation; + } + catch (tf2::TransformException& ex) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping goal metadata append: " + "Could not get goal transform for %s to %s: %s", + base_frame.c_str(), plan_request.header.frame_id.c_str(), + ex.what()); + + // (Can't. Copy not supported.) + // *metadata = original; // Undo our changes. + return false; + } + } + + tf2::Quaternion tf2_quat_frame_offset( + quat_offset.x, quat_offset.y, quat_offset.z, quat_offset.w); + tf2_quat_frame_offset.normalize(); + + size_t waypoint_idx = 0; + for (auto& waypoint : plan_request.waypoints) + { + std::string meta_name = "waypoints_" + std::to_string(waypoint_idx++); + + // Apply offsets + // Position + query_append_range_inclusive_with_tolerance( + query, meta_name + ".position.x", + x_offset + waypoint.position.x, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".position.y", + y_offset+ waypoint.position.y, match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".position.z", + z_offset+waypoint.position.z, match_tolerance); + + // Orientation + tf2::Quaternion tf2_quat_goal_offset( + waypoint.orientation.x, + waypoint.orientation.y, + waypoint.orientation.z, + waypoint.orientation.w); + tf2_quat_goal_offset.normalize(); + + auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; + final_quat.normalize(); + + query_append_range_inclusive_with_tolerance( + query, meta_name + ".orientation.x", final_quat.getX(), match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".orientation.y", final_quat.getY(), match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".orientation.z", final_quat.getZ(), match_tolerance); + query_append_range_inclusive_with_tolerance( + query, meta_name + ".orientation.w", final_quat.getW(), match_tolerance); + } + + query.append("link_name", plan_request.link_name); + + return true; +} + +// CARTESIAN PLAN CACHING: METADATA CONSTRUCTION +bool +MotionPlanCache::extract_and_append_cartesian_plan_start_to_metadata( + Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request) +{ + // Make ignored members explicit + if (!plan_request.start_state.multi_dof_joint_state.joint_names.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.multi_dof_joint_states: Not supported."); + } + if (!plan_request.start_state.attached_collision_objects.empty()) + { + RCLCPP_WARN( + node_->get_logger(), + "Ignoring start_state.attached_collision_objects: Not supported."); + } + + // auto original = *metadata; // Copy not supported. + + metadata.append("group_name", plan_request.group_name); + + // Joint state + // Only accounts for joint_state position. Ignores velocity and effort. + if (plan_request.start_state.is_diff) + { + // If plan request states that the start_state is_diff, then we need to get + // the current state from the move_group. + + // NOTE: methyldragon - + // I think if is_diff is on, the joint states will not be populated in all + // of our motion plan requests? If this isn't the case we might need to + // apply the joint states as offsets as well. + // + // TODO: Since MoveIt also potentially does another getCurrentState() call + // when planning, there is a chance that the current state in the cache + // differs from the state used in MoveIt's plan. + // + // When upstreaming this class to MoveIt, this issue should go away once + // the class is used within the move group's Plan call. + moveit::core::RobotStatePtr current_state = move_group.getCurrentState(); + if (!current_state) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping start metadata append: Could not get robot state."); + // *metadata = original; // Undo our changes. // Copy not supported + return false; + } + + moveit_msgs::msg::RobotState current_state_msg; + robotStateToRobotStateMsg(*current_state, current_state_msg); + + for (size_t i = 0; i < current_state_msg.joint_state.name.size(); i++) + { + metadata.append( + "start_state.joint_state.name_" + std::to_string(i), + current_state_msg.joint_state.name.at(i)); + metadata.append( + "start_state.joint_state.position_" + std::to_string(i), + current_state_msg.joint_state.position.at(i)); + } + } + else + { + for ( + size_t i = 0; i < plan_request.start_state.joint_state.name.size(); i++ + ) + { + metadata.append( + "start_state.joint_state.name_" + std::to_string(i), + plan_request.start_state.joint_state.name.at(i)); + metadata.append( + "start_state.joint_state.position_" + std::to_string(i), + plan_request.start_state.joint_state.position.at(i)); + } + } + + return true; +} + +bool +MotionPlanCache::extract_and_append_cartesian_plan_goal_to_metadata( + Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request) +{ + // Make ignored members explicit + if (plan_request.path_constraints.joint_constraints.empty() || + plan_request.path_constraints.position_constraints.empty() || + plan_request.path_constraints.orientation_constraints.empty() || + plan_request.path_constraints.visibility_constraints.empty()) + { + RCLCPP_WARN( + node_->get_logger(), "Ignoring path_constraints: Not supported."); + } + if (plan_request.avoid_collisions) + { + RCLCPP_WARN(node_->get_logger(), + "Ignoring avoid_collisions: Not supported."); + } + + // auto original = *metadata; // Copy not supported. + + metadata.append("max_velocity_scaling_factor", + plan_request.max_velocity_scaling_factor); + metadata.append("max_acceleration_scaling_factor", + plan_request.max_acceleration_scaling_factor); + metadata.append("max_step", plan_request.max_step); + metadata.append("jump_threshold", plan_request.jump_threshold); + + // Waypoints + // Restating them in terms of the robot model frame (usually base_link) + std::string base_frame = move_group.getRobotModel()->getModelFrame(); + + // Compute offsets. + double x_offset = 0; + double y_offset = 0; + double z_offset = 0; + + geometry_msgs::msg::Quaternion quat_offset; + quat_offset.x = 0; + quat_offset.y = 0; + quat_offset.z = 0; + quat_offset.w = 1; + + if (base_frame != plan_request.header.frame_id) + { + try + { + auto transform = tf_buffer_->lookupTransform( + plan_request.header.frame_id, base_frame, tf2::TimePointZero); + + x_offset = transform.transform.translation.x; + y_offset = transform.transform.translation.y; + z_offset = transform.transform.translation.z; + quat_offset = transform.transform.rotation; + } + catch (tf2::TransformException& ex) + { + RCLCPP_WARN( + node_->get_logger(), + "Skipping goal metadata append: " + "Could not get goal transform for %s to %s: %s", + base_frame.c_str(), plan_request.header.frame_id.c_str(), + ex.what()); + + // (Can't. Copy not supported.) + // *metadata = original; // Undo our changes. + return false; + } + } + + tf2::Quaternion tf2_quat_frame_offset( + quat_offset.x, quat_offset.y, quat_offset.z, quat_offset.w); + tf2_quat_frame_offset.normalize(); + + size_t waypoint_idx = 0; + for (auto& waypoint : plan_request.waypoints) + { + std::string meta_name = "waypoints_" + std::to_string(waypoint_idx++); + + // Apply offsets + // Position + metadata.append(meta_name + ".position.x", x_offset + waypoint.position.x); + metadata.append(meta_name + ".position.y", y_offset + waypoint.position.y); + metadata.append(meta_name + ".position.z", z_offset + waypoint.position.z); + + // Orientation + tf2::Quaternion tf2_quat_goal_offset( + waypoint.orientation.x, + waypoint.orientation.y, + waypoint.orientation.z, + waypoint.orientation.w); + tf2_quat_goal_offset.normalize(); + + auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; + final_quat.normalize(); + + metadata.append(meta_name + ".orientation.x", final_quat.getX()); + metadata.append(meta_name + ".orientation.y", final_quat.getY()); + metadata.append(meta_name + ".orientation.z", final_quat.getZ()); + metadata.append(meta_name + ".orientation.w", final_quat.getW()); + } + + metadata.append("link_name", plan_request.link_name); + metadata.append("header.frame_id", base_frame); + + return true; +} + +} // namespace motion_planner +} // namespace nexus diff --git a/nexus_motion_planner/src/motion_plan_cache.hpp b/nexus_motion_planner/src/motion_plan_cache.hpp new file mode 100644 index 0000000..fc7bbff --- /dev/null +++ b/nexus_motion_planner/src/motion_plan_cache.hpp @@ -0,0 +1,274 @@ +// Copyright 2022 Johnson & Johnson +// +// 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. + +#ifndef SRC__MOTION_PLAN_CACHE_HPP +#define SRC__MOTION_PLAN_CACHE_HPP + +#include +#include +#include + +#include +#include + +#include + +// TF2 +#include +#include + +// ROS2 Messages +#include +#include +#include + +// moveit modules +#include +#include + +// NEXUS messages +#include + +namespace nexus { +namespace motion_planner { + +/** + * Cache manager for the Nexus motion planner. + * + * This manager facilitates cache management for MoveIt 2's `MoveGroupInterface` + * by using `warehouse_ros` to manage a database of executed motion plans, and + * how long they took to execute. This allows for the lookup and reuse of the + * best performing plans found so far. + * + * WARNING: + * This cache does NOT support collision detection! + * Plans will be put into and fetched from the cache IGNORING collision. + * If your planning scene is expected to change between cache lookups, do NOT + * use this cache, fetched plans are likely to result in collision then. + * + * To handle collisions this class will need to hash the planning scene world + * msg (after zeroing out std_msgs/Header timestamps and sequences) and do an + * appropriate lookup. + * + * Relevant ROS Parameters: + * - `warehouse_plugin`: What database to use + * - `warehouse_host`: Where the database should be created + * - `warehouse_port`: The port used for the database + * + * Motion plans are stored in the `move_group_plan_cache` database within the + * database file, with plans for each move group stored in a collection named + * after the relevant move group's name. + * + * For example, the "my_move_group" move group will have its cache stored in + * `move_group_plan_cache@my_move_group` + * + * Motion plans are keyed on: + * - Plan Start: robot joint state + * - Plan Goal (either of): + * - Final pose (wrt. `planning_frame` (usually `base_link`)) + * - Final robot joint states + * + * Motion plans may be looked up with some tolerance at call time. + */ +class MotionPlanCache +{ +public: + // We explicitly need a Node::SharedPtr because warehouse_ros ONLY supports + // it... + explicit MotionPlanCache(const rclcpp::Node::SharedPtr& node); + + bool init( + const std::string& db_path = ":memory:", + uint32_t db_port = 0, + double exact_match_precision = 1e-6); + + // =========================================================================== + // MOTION PLAN CACHING + // =========================================================================== + // TOP LEVEL OPS + + // Fetches all plans that fit within the requested tolerances for start and + // goal conditions, returning them as a vector, sorted by some db column. + std::vector< + warehouse_ros::MessageWithMetadata< + moveit_msgs::msg::RobotTrajectory + >::ConstPtr + > + fetch_all_matching_plans( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double start_tolerance, + double goal_tolerance, + bool metadata_only = false, + const std::string& sort_by = "execution_time_s"); + + // Fetches the best plan that fits within the requested tolerances for start + // and goal conditions, by some db column. + warehouse_ros::MessageWithMetadata< + moveit_msgs::msg::RobotTrajectory + >::ConstPtr + fetch_best_matching_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double start_tolerance, + double goal_tolerance, + bool metadata_only = false, + const std::string& sort_by = "execution_time_s"); + + // Put a plan into the database if it is the best matching plan seen so far. + // + // Plans are matched based off their start and goal states. + // And are considered "better" if they have a smaller planned execution time + // than matching plans. + // + // Optionally deletes all worse plans by default to prune the cache. + bool put_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + const moveit_msgs::msg::RobotTrajectory& plan, + double execution_time_s, + double planning_time_s, + bool delete_worse_plans = true); + + // QUERY CONSTRUCTION + bool extract_and_append_plan_start_to_query( + warehouse_ros::Query& query, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double match_tolerance); + + bool extract_and_append_plan_goal_to_query( + warehouse_ros::Query& query, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::msg::MotionPlanRequest& plan_request, + double match_tolerance); + + // METADATA CONSTRUCTION + bool extract_and_append_plan_start_to_metadata( + warehouse_ros::Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::msg::MotionPlanRequest& plan_request); + + bool extract_and_append_plan_goal_to_metadata( + warehouse_ros::Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::msg::MotionPlanRequest& plan_request); + + // =========================================================================== + // CARTESIAN PLAN CACHING + // =========================================================================== + // TOP LEVEL OPS + + // This mimics the move group computeCartesianPath signature (without path + // constraints). + moveit_msgs::srv::GetCartesianPath::Request + construct_get_cartesian_plan_request( + moveit::planning_interface::MoveGroupInterface& move_group, + const std::vector& waypoints, + double step, + double jump_threshold, + bool avoid_collisions = true); + + // Fetches all cartesian plans that fit within the requested tolerances for + // start and goal conditions, returning them as a vector, sorted by some db + // column. + std::vector< + warehouse_ros::MessageWithMetadata< + moveit_msgs::msg::RobotTrajectory + >::ConstPtr + > + fetch_all_matching_cartesian_plans( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double min_fraction, + double start_tolerance, + double goal_tolerance, + bool metadata_only = false, + const std::string& sort_by = "execution_time_s"); + + // Fetches the best cartesian plan that fits within the requested tolerances + // for start and goal conditions, by some db column. + warehouse_ros::MessageWithMetadata< + moveit_msgs::msg::RobotTrajectory + >::ConstPtr + fetch_best_matching_cartesian_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double min_fraction, + double start_tolerance, + double goal_tolerance, + bool metadata_only = false, + const std::string& sort_by = "execution_time_s"); + + // Put a cartesian plan into the database if it is the best matching cartesian + // plan seen so far. + // + // Cartesian plans are matched based off their start and goal states. + // And are considered "better" if they have a smaller planned execution time + // than matching cartesian plans. + // + // Optionally deletes all worse cartesian plans by default to prune the cache. + bool put_cartesian_plan( + const moveit::planning_interface::MoveGroupInterface& move_group, + const std::string& move_group_namespace, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + const moveit_msgs::msg::RobotTrajectory& plan, + double execution_time_s, + double planning_time_s, + double fraction, + bool delete_worse_plans = true); + + // QUERY CONSTRUCTION + bool extract_and_append_cartesian_plan_start_to_query( + warehouse_ros::Query& query, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double match_tolerance); + + bool extract_and_append_cartesian_plan_goal_to_query( + warehouse_ros::Query& query, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request, + double match_tolerance); + + // METADATA CONSTRUCTION + bool extract_and_append_cartesian_plan_start_to_metadata( + warehouse_ros::Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request); + + bool extract_and_append_cartesian_plan_goal_to_metadata( + warehouse_ros::Metadata& metadata, + const moveit::planning_interface::MoveGroupInterface& move_group, + const moveit_msgs::srv::GetCartesianPath::Request& plan_request); + +private: + rclcpp::Node::SharedPtr node_; + warehouse_ros::DatabaseConnection::Ptr db_; + + double exact_match_precision_ = 1e-6; + + std::unique_ptr tf_buffer_; + std::shared_ptr tf_listener_; +}; + +} // namespace planning_interface +} // namespace moveit + +#endif // SRC__MOTION_PLAN_CACHE_HPP \ No newline at end of file diff --git a/nexus_motion_planner/src/motion_planner_server.cpp b/nexus_motion_planner/src/motion_planner_server.cpp index 9c53046..2c3ce5e 100644 --- a/nexus_motion_planner/src/motion_planner_server.cpp +++ b/nexus_motion_planner/src/motion_planner_server.cpp @@ -12,8 +12,62 @@ // See the License for the specific language governing permissions and // limitations under the License. +// TODO: Catch warehouse_ros exceptions if they are thrown. + #include "motion_planner_server.hpp" +std::string str_tolower(std::string s) +{ + std::transform(s.begin(), s.end(), s.begin(), + [](unsigned char c) { return std::tolower(c); } + ); + return s; +} + +namespace nexus { +namespace motion_planner { + +constexpr bool cache_mode_is_execute(PlannerDatabaseMode mode) +{ + return mode == PlannerDatabaseMode::ExecuteBestEffort || + mode == PlannerDatabaseMode::ExecuteReadOnly; +} + +constexpr bool cache_mode_is_training(PlannerDatabaseMode mode) +{ + return mode == PlannerDatabaseMode::TrainingOverwrite || + mode == PlannerDatabaseMode::TrainingAppendOnly; +} + +// Convert planner database string param to PlannerDatabaseMode enum values. +PlannerDatabaseMode str_to_planner_database_mode(std::string s) +{ + std::string s_lower = str_tolower(s); + + // Using a switch-case here is... inconvenient (needs constexpr hashing or a + // map), so we don't. + if (s_lower == "training_overwrite" || s_lower == "trainingoverwrite") + { + return PlannerDatabaseMode::TrainingOverwrite; + } + else if (s_lower == "training_append_only" || s_lower == "trainingappendonly") + { + return PlannerDatabaseMode::TrainingAppendOnly; + } + else if (s_lower == "execute_best_effort" || s_lower == "executebesteffort") + { + return PlannerDatabaseMode::ExecuteBestEffort; + } + else if (s_lower == "execute_read_only" || s_lower == "executereadonly") + { + return PlannerDatabaseMode::ExecuteReadOnly; + } + else + { + return PlannerDatabaseMode::Unset; + } +} + //============================================================================== MotionPlannerServer::MotionPlannerServer(const rclcpp::NodeOptions& options) : rclcpp_lifecycle::LifecycleNode("motion_planner_server", options) @@ -162,6 +216,78 @@ MotionPlannerServer::MotionPlannerServer(const rclcpp::NodeOptions& options) "Setting parameter get_state_wait_seconds to [%.3f]", _get_state_wait_seconds ); + + // Motion plan cache params + // unset, training, training_append_only, execute_best_effort, execute_read_only + _planner_database_mode = this->declare_parameter( + "planner_database_mode", "unset"); + RCLCPP_INFO( + this->get_logger(), + "Setting parameter planner_database_mode to [%s]", + _planner_database_mode.c_str() + ); + _cache_mode = str_to_planner_database_mode(_planner_database_mode); + + _cache_db_plugin = this->declare_parameter( + "cache_db_plugin", "warehouse_ros_sqlite::DatabaseConnection"); + RCLCPP_INFO( + this->get_logger(), + "Setting parameter cache_db_plugin to [%s]", _cache_db_plugin.c_str() + ); + + _cache_db_host = this->declare_parameter("cache_db_host", ":memory:"); + RCLCPP_INFO( + this->get_logger(), + "Setting parameter cache_db_host to [%s]", _cache_db_host.c_str() + ); + + _cache_db_port = this->declare_parameter("cache_db_port", 0); + RCLCPP_INFO( + this->get_logger(), + "Setting parameter cache_db_port to [%d]", _cache_db_port + ); + + // For floating point comparison, what counts as an "exact" match. + _cache_exact_match_tolerance = this->declare_parameter( + "cache_exact_match_tolerance", 0.0005); // ~0.028 degrees per joint + RCLCPP_INFO( + this->get_logger(), + "Setting parameter cache_exact_match_tolerance to [%.2e]", + _cache_exact_match_tolerance + ); + + _cache_start_match_tolerance = this->declare_parameter( + "cache_start_match_tolerance", 0.025); + RCLCPP_INFO( + this->get_logger(), + "Setting parameter cache_start_match_tolerance to [%.5f]", + _cache_start_match_tolerance + ); + + _cache_goal_match_tolerance = this->declare_parameter( + "cache_goal_match_tolerance", 0.001); + RCLCPP_INFO( + this->get_logger(), + "Setting parameter cache_goal_match_tolerance to [%.5f]", + _cache_goal_match_tolerance + ); + + if (_cache_mode != PlannerDatabaseMode::Unset) + { + // Push warehouse_ros parameters to internal node + // This must happen BEFORE the MotionPlanCache is created! + _internal_node->declare_parameter( + "warehouse_plugin", _cache_db_plugin); + + _internal_node->declare_parameter( + "warehouse_host", _cache_db_host); + + _internal_node->declare_parameter( + "warehouse_port", _cache_db_port); + + _motion_plan_cache = + std::make_unique(_internal_node); + } } //============================================================================== @@ -178,6 +304,17 @@ auto MotionPlannerServer::on_configure(const LifecycleState& /*state*/) -> CallbackReturn { RCLCPP_INFO(this->get_logger(), "Configuring..."); + + if (_cache_mode != PlannerDatabaseMode::Unset) + { + if (!_motion_plan_cache->init( + _cache_db_host, _cache_db_port, _cache_exact_match_tolerance)) + { + RCLCPP_ERROR(this->get_logger(), "Could not init motion plan cache."); + return CallbackReturn::ERROR; + } + } + if (_use_move_group_interfaces) { auto ok = initialize_move_group_interfaces(); @@ -322,8 +459,7 @@ auto MotionPlannerServer::on_shutdown(const LifecycleState& /*state*/) //============================================================================== void MotionPlannerServer::plan_with_move_group( - const GetMotionPlanService::ServiceType::Request& req, - Response res) + const GetMotionPlanService::ServiceType::Request& req, Response res) { RCLCPP_INFO( this->get_logger(), @@ -461,6 +597,7 @@ void MotionPlannerServer::plan_with_move_group( interface->setMaxVelocityScalingFactor(vel_scale); interface->setMaxAccelerationScalingFactor(acc_scale); moveit::core::MoveItErrorCode error; + moveit_msgs::msg::MotionPlanRequest plan_req_msg; // For caching if (req.cartesian) { std::vector waypoints; @@ -468,42 +605,232 @@ void MotionPlannerServer::plan_with_move_group( // TODO(YV): For now we use simple cartesian interpolation. OMPL supports // constrained planning so we can consider adding orientation or line // constraints to the end-effector link instead and call plan(). - const double error = interface->computeCartesianPath( - waypoints, - _cartesian_max_step, - _cartesian_jump_threshold, - res->result.trajectory, - _collision_aware_cartesian_path - ); - RCLCPP_INFO( - this->get_logger(), - "Cartesian interpolation returned a fraction of [%.2f]", error - ); - if (error <= 0.0) + + moveit_msgs::msg::RobotTrajectory cartesian_plan; + double fraction; + bool cartesian_plan_is_from_cache = false; + auto cartesian_plan_req_msg = + _motion_plan_cache->construct_get_cartesian_plan_request( + *interface, waypoints, _cartesian_max_step, _cartesian_jump_threshold, + _collision_aware_cartesian_path); + + // Fetch if in execute mode. + if (cache_mode_is_execute(_cache_mode)) + { + auto fetch_start = this->now(); + auto fetched_cartesian_plan = + _motion_plan_cache->fetch_best_matching_cartesian_plan( + *interface, robot_name, cartesian_plan_req_msg, + /* min_fraction */ 1.0, + _cache_start_match_tolerance, _cache_goal_match_tolerance); + auto fetch_end = this->now(); + // Set plan if a cached cartesian plan was fetched. + if (fetched_cartesian_plan) + { + fraction = fetched_cartesian_plan->lookupDouble("fraction"); + cartesian_plan_is_from_cache = true; + cartesian_plan = *fetched_cartesian_plan; + res->result.error_code.val = + moveit_msgs::msg::MoveItErrorCodes::SUCCESS; + res->result.planning_time = (fetch_end - fetch_start).seconds(); + RCLCPP_INFO( + this->get_logger(), + "Cache fetch took %es, planning time of fetched plan was: %es", + (fetch_end - fetch_start).seconds(), + fetched_cartesian_plan->lookupDouble("planning_time_s")); + } + // Fail if ReadOnly mode and no cached cartesian plan was fetched. + else if (_cache_mode == PlannerDatabaseMode::ExecuteReadOnly) + { + RCLCPP_ERROR( + this->get_logger(), + "Cache mode was ExecuteReadOnly, and could not find " + "cached cartesian plan for cartesian plan request: \n\n%s", + moveit_msgs::srv::to_yaml(cartesian_plan_req_msg).c_str()); + res->result.error_code.val = + moveit_msgs::msg::MoveItErrorCodes::FAILURE; + return; + } + } + + // Plan if needed. + // This is if we didn't fetch a cartesian plan from the cache. + // (In training or unset mode we never attempt to fetch, so it will always + // plan.) + if (!cartesian_plan_is_from_cache) { - res->result.error_code.val = -1; + auto cartesian_plan_start = this->now(); + fraction = interface->computeCartesianPath( + waypoints, + _cartesian_max_step, + _cartesian_jump_threshold, + cartesian_plan, + _collision_aware_cartesian_path + ); + auto cartesian_plan_end = this->now(); + + RCLCPP_INFO( + this->get_logger(), + "Cartesian interpolation returned a fraction of [%.2f]", fraction + ); + if (fraction <= 0.0) + { + res->result.error_code.val = -1; + } + else + { + res->result.error_code.val = 1; + } + + res->result.planning_time = + (cartesian_plan_end - cartesian_plan_start).seconds(); + + RCLCPP_INFO( + this->get_logger(), + "Plan status: %d, planning time: %es", + res->result.error_code.val, res->result.planning_time); } else { - res->result.error_code.val = 1; + if (fraction <= 0) + { + res->result.error_code.val = -1; + } + else + { + res->result.error_code.val = 1; + } + } + + // Do NOT move this. We use the cartesian_plan_req_msg later. + res->result.trajectory_start = cartesian_plan_req_msg.start_state; + res->result.trajectory = std::move(cartesian_plan); + + if (res->result.error_code.val != + moveit_msgs::msg::MoveItErrorCodes::SUCCESS) + { + RCLCPP_WARN( + this->get_logger(), + "Cartesian planning did not succeed: %d", res->result.error_code.val); + return; + } + // Put plan if in training mode. + // Make sure we check if the plan we have was fetched (so we don't have + // duplicate caches.) + if (cache_mode_is_training(_cache_mode) && !cartesian_plan_is_from_cache) + { + if (!_motion_plan_cache->put_cartesian_plan( + *interface, robot_name, + std::move(cartesian_plan_req_msg), std::move(res->result.trajectory), + rclcpp::Duration( + res->result.trajectory.joint_trajectory.points.back() + .time_from_start + ).seconds(), + res->result.planning_time, fraction, + _cache_mode == PlannerDatabaseMode::TrainingOverwrite)) + { + RCLCPP_WARN( + this->get_logger(), "Did not put cartesian plan into cache."); + } } } else { MoveGroupInterface::Plan plan; - res->result.error_code = interface->plan(plan); + bool plan_is_from_cache = false; + interface->constructMotionPlanRequest(plan_req_msg); + + // Fetch if in execute mode. + if (cache_mode_is_execute(_cache_mode)) + { + auto fetch_start = this->now(); + auto fetched_plan = _motion_plan_cache->fetch_best_matching_plan( + *interface, robot_name, plan_req_msg, + _cache_start_match_tolerance, _cache_goal_match_tolerance); + auto fetch_end = this->now(); + // Set plan if a cached plan was fetched. + if (fetched_plan) + { + plan_is_from_cache = true; + plan.start_state = plan_req_msg.start_state; + plan.trajectory = *fetched_plan; + plan.planning_time = (fetch_end - fetch_start).seconds(); + res->result.error_code.val = + moveit_msgs::msg::MoveItErrorCodes::SUCCESS; + RCLCPP_INFO( + this->get_logger(), + "Cache fetch took %es, planning time of fetched plan was: %es", + (fetch_end - fetch_start).seconds(), + fetched_plan->lookupDouble("planning_time_s")); + } + // Fail if ReadOnly mode and no cached plan was fetched. + else if (_cache_mode == PlannerDatabaseMode::ExecuteReadOnly) + { + RCLCPP_ERROR( + this->get_logger(), + "Cache mode was ExecuteReadOnly, and could not find " + "cached plan for plan request: \n\n%s", + moveit_msgs::msg::to_yaml(plan_req_msg).c_str()); + res->result.error_code.val = + moveit_msgs::msg::MoveItErrorCodes::FAILURE; + return; + } + } + + // Plan if needed. + // This is if we didn't fetch a plan from the cache. + // (In training or unset mode we never attempt to fetch, so it will always + // plan.) + if (!plan_is_from_cache) + { + res->result.error_code = interface->plan(plan); + RCLCPP_INFO( + this->get_logger(), + "Plan status: %d, planning time: %es", + res->result.error_code.val, plan.planning_time); + } + res->result.trajectory_start = std::move(plan.start_state); res->result.trajectory = std::move(plan.trajectory); res->result.planning_time = std::move(plan.planning_time); + + if (res->result.error_code.val != + moveit_msgs::msg::MoveItErrorCodes::SUCCESS) + { + RCLCPP_WARN( + this->get_logger(), + "Planning did not succeed: %d", res->result.error_code.val); + return; + } + + // Put plan if in training mode. + // Make sure we check if the plan we have was fetched (so we don't have + // duplicate caches.) + if (cache_mode_is_training(_cache_mode) && !plan_is_from_cache) + { + if (!_motion_plan_cache->put_plan( + *interface, robot_name, + std::move(plan_req_msg), std::move(res->result.trajectory), + rclcpp::Duration( + res->result.trajectory.joint_trajectory.points.back() + .time_from_start + ).seconds(), + res->result.planning_time, + _cache_mode == PlannerDatabaseMode::TrainingOverwrite)) + { + RCLCPP_WARN(this->get_logger(), "Did not put plan into cache."); + } + } } if (_execute_trajectory) { - RCLCPP_INFO( - this->get_logger(), - "Executing trajectory!"); + RCLCPP_INFO(this->get_logger(), "Executing trajectory!"); // This is a blocking call. interface->execute(res->result.trajectory); } return; } + +} // namespace planning_interface +} // namespace moveit \ No newline at end of file diff --git a/nexus_motion_planner/src/motion_planner_server.hpp b/nexus_motion_planner/src/motion_planner_server.hpp index 050929f..7451d7a 100644 --- a/nexus_motion_planner/src/motion_planner_server.hpp +++ b/nexus_motion_planner/src/motion_planner_server.hpp @@ -35,6 +35,36 @@ // NEXUS messages #include +// NEXUS motion plan cache +#include "motion_plan_cache.hpp" + +namespace nexus { +namespace motion_planner { + +enum class PlannerDatabaseMode : uint8_t +{ + // Unset. Planner will not use a cache. + Unset = 0, + + // Planner will always generate a plan. + // It will add plans to the database if they are the best seen so far. + // Will overwrite close-enough entries if a better plan was found. + TrainingOverwrite = 10, + + // Planner will always generate a plan. + // It will add plans to the database if they are the best seen so far. + // Will not overwrite any existing entries. + TrainingAppendOnly = 11, + + // Planner will prioritize returning plans in the cache. + // If no plan was found, it will instead attempt to generate a plan live, but will not update the + // cache. + ExecuteBestEffort = 20, + + // Planner will return a plan only if present in the database cache. + ExecuteReadOnly = 21, +}; + //============================================================================== class MotionPlannerServer : public rclcpp_lifecycle::LifecycleNode { @@ -69,6 +99,7 @@ class MotionPlannerServer : public rclcpp_lifecycle::LifecycleNode rclcpp::Node::SharedPtr _internal_node; std::thread _spin_thread; + // MoveIt planning std::vector _manipulators; bool _use_move_group_interfaces; bool _use_namespace; @@ -88,6 +119,18 @@ class MotionPlannerServer : public rclcpp_lifecycle::LifecycleNode double _workspace_max_y; double _workspace_max_z; + // Motion plan caching + std::unique_ptr _motion_plan_cache; + std::string _planner_database_mode; + PlannerDatabaseMode _cache_mode = PlannerDatabaseMode::Unset; + + std::string _cache_db_plugin; + std::string _cache_db_host; + int _cache_db_port; + double _cache_exact_match_tolerance; // for floating point comparison + double _cache_start_match_tolerance; + double _cache_goal_match_tolerance; + rclcpp::Service::SharedPtr _plan_srv; std::unordered_map> @@ -102,4 +145,7 @@ class MotionPlannerServer : public rclcpp_lifecycle::LifecycleNode Response res); }; // class MotionPlannerServer +} // namespace planning_interface +} // namespace moveit + #endif // SRC__MOTION_PLANNER_SERVER_HPP