From 6ad592e61ec66219f2e7fe4b04cd0747a5d3d3ef Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 11:37:13 -0800 Subject: [PATCH 01/13] Remove query appending macro Signed-off-by: methylDragon --- .../src/motion_plan_cache.cpp | 184 ++++++++---------- 1 file changed, 81 insertions(+), 103 deletions(-) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index 3541f9c..a0bdb20 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -26,13 +26,18 @@ namespace nexus { namespace motion_planner { -#define NEXUS_MATCH_RANGE(arg, tolerance) \ - arg - tolerance / 2, arg + tolerance / 2 - using warehouse_ros::MessageWithMetadata; using warehouse_ros::Metadata; using warehouse_ros::Query; +// Append a range inclusive query with some tolerance about some center value. +void queryAppendRangeInclusiveWithTolerance( + Query& query, const std::string& name, double center, double tolerance) +{ + query.appendRangeInclusive( + name, center - tolerance / 2, center + tolerance / 2); +} + MotionPlanCache::MotionPlanCache(const rclcpp::Node::SharedPtr& node) : node_(node) { @@ -336,11 +341,9 @@ MotionPlanCache::extract_and_append_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), current_state_msg.joint_state.name.at(i)); - query.appendRangeInclusive( - "start_state.joint_state.position_" + std::to_string(i), - NEXUS_MATCH_RANGE( - current_state_msg.joint_state.position.at(i), match_tolerance) - ); + queryAppendRangeInclusiveWithTolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + current_state_msg.joint_state.position.at(i), match_tolerance); } } else @@ -352,11 +355,9 @@ MotionPlanCache::extract_and_append_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), plan_request.start_state.joint_state.name.at(i)); - query.appendRangeInclusive( - "start_state.joint_state.position_" + std::to_string(i), - NEXUS_MATCH_RANGE( - plan_request.start_state.joint_state.position.at(i), match_tolerance) - ); + queryAppendRangeInclusiveWithTolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + plan_request.start_state.joint_state.position.at(i), match_tolerance); } } return true; @@ -398,19 +399,15 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( // auto original = *query; // Copy not supported. - query.appendRangeInclusive( - "max_velocity_scaling_factor", - NEXUS_MATCH_RANGE( - plan_request.max_velocity_scaling_factor, match_tolerance) - ); - query.appendRangeInclusive( - "max_acceleration_scaling_factor", - NEXUS_MATCH_RANGE( - plan_request.max_acceleration_scaling_factor, match_tolerance) - ); - query.appendRangeInclusive( - "max_cartesian_speed", - NEXUS_MATCH_RANGE(plan_request.max_cartesian_speed, match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, "max_velocity_scaling_factor", + plan_request.max_velocity_scaling_factor, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, "max_acceleration_scaling_factor", + plan_request.max_acceleration_scaling_factor, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + 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; @@ -440,13 +437,10 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( "goal_constraints.joint_constraints_" + std::to_string(joint_idx++); query.append(meta_name + ".joint_name", constraint.joint_name); - query.appendRangeInclusive( - meta_name + ".position", - NEXUS_MATCH_RANGE(constraint.position, match_tolerance)); - query.appendGTE( - meta_name + ".tolerance_above", constraint.tolerance_above); - query.appendLTE( - meta_name + ".tolerance_below", constraint.tolerance_below); + queryAppendRangeInclusiveWithTolerance( + 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 @@ -501,18 +495,15 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( query.append(meta_name + ".link_name", constraint.link_name); - query.appendRangeInclusive( - meta_name + ".target_point_offset.x", - NEXUS_MATCH_RANGE( - x_offset + constraint.target_point_offset.x, match_tolerance)); - query.appendRangeInclusive( - meta_name + ".target_point_offset.y", - NEXUS_MATCH_RANGE( - y_offset + constraint.target_point_offset.y, match_tolerance)); - query.appendRangeInclusive( - meta_name + ".target_point_offset.z", - NEXUS_MATCH_RANGE( - z_offset + constraint.target_point_offset.z, match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".target_point_offset.x", + x_offset + constraint.target_point_offset.x, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".target_point_offset.y", + y_offset + constraint.target_point_offset.y, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".target_point_offset.z", + z_offset + constraint.target_point_offset.z, match_tolerance); } } @@ -586,18 +577,18 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; final_quat.normalize(); - query.appendRangeInclusive( - meta_name + ".target_point_offset.x", - NEXUS_MATCH_RANGE(final_quat.getX(), match_tolerance)); - query.appendRangeInclusive( - meta_name + ".target_point_offset.y", - NEXUS_MATCH_RANGE(final_quat.getY(), match_tolerance)); - query.appendRangeInclusive( - meta_name + ".target_point_offset.z", - NEXUS_MATCH_RANGE(final_quat.getZ(), match_tolerance)); - query.appendRangeInclusive( - meta_name + ".target_point_offset.w", - NEXUS_MATCH_RANGE(final_quat.getW(), match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".target_point_offset.x", + final_quat.getX(), match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".target_point_offset.y", + final_quat.getY(), match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".target_point_offset.z", + final_quat.getZ(), match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".target_point_offset.w", + final_quat.getW(), match_tolerance); } } @@ -1208,10 +1199,9 @@ MotionPlanCache::extract_and_append_cartesian_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), current_state_msg.joint_state.name.at(i)); - query.appendRangeInclusive( - "start_state.joint_state.position_" + std::to_string(i), - NEXUS_MATCH_RANGE( - current_state_msg.joint_state.position.at(i), match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + current_state_msg.joint_state.position.at(i), match_tolerance); } } else @@ -1223,11 +1213,9 @@ MotionPlanCache::extract_and_append_cartesian_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), plan_request.start_state.joint_state.name.at(i)); - query.appendRangeInclusive( - "start_state.joint_state.position_" + std::to_string(i), - NEXUS_MATCH_RANGE( - plan_request.start_state.joint_state.position.at(i), - match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, "start_state.joint_state.position_" + std::to_string(i), + plan_request.start_state.joint_state.position.at(i), match_tolerance); } } @@ -1260,20 +1248,16 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( // auto original = *metadata; // Copy not supported. - query.appendRangeInclusive( - "max_velocity_scaling_factor", - NEXUS_MATCH_RANGE( - plan_request.max_velocity_scaling_factor, match_tolerance)); - query.appendRangeInclusive( - "max_acceleration_scaling_factor", - NEXUS_MATCH_RANGE( - plan_request.max_acceleration_scaling_factor, match_tolerance)); - query.appendRangeInclusive( - "max_step", - NEXUS_MATCH_RANGE(plan_request.max_step, match_tolerance)); - query.appendRangeInclusive( - "jump_threshold", - NEXUS_MATCH_RANGE(plan_request.jump_threshold, match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, "max_velocity_scaling_factor", + plan_request.max_velocity_scaling_factor, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, "max_acceleration_scaling_factor", + plan_request.max_acceleration_scaling_factor, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, "max_step", plan_request.max_step, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, "jump_threshold", plan_request.jump_threshold, match_tolerance); // Waypoints // Restating them in terms of the robot model frame (usually base_link) @@ -1328,15 +1312,15 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( // Apply offsets // Position - query.appendRangeInclusive( - meta_name + ".position.x", - NEXUS_MATCH_RANGE(x_offset + waypoint.position.x, match_tolerance)); - query.appendRangeInclusive( - meta_name + ".position.y", - NEXUS_MATCH_RANGE(y_offset+ waypoint.position.y, match_tolerance)); - query.appendRangeInclusive( - meta_name + ".position.z", - NEXUS_MATCH_RANGE(z_offset+waypoint.position.z, match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".position.x", + x_offset + waypoint.position.x, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".position.y", + y_offset+ waypoint.position.y, match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".position.z", + z_offset+waypoint.position.z, match_tolerance); // Orientation tf2::Quaternion tf2_quat_goal_offset( @@ -1349,18 +1333,14 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; final_quat.normalize(); - query.appendRangeInclusive( - meta_name + ".orientation.x", - NEXUS_MATCH_RANGE(final_quat.getX(), match_tolerance)); - query.appendRangeInclusive( - meta_name + ".orientation.y", - NEXUS_MATCH_RANGE(final_quat.getY(), match_tolerance)); - query.appendRangeInclusive( - meta_name + ".orientation.z", - NEXUS_MATCH_RANGE(final_quat.getZ(), match_tolerance)); - query.appendRangeInclusive( - meta_name + ".orientation.w", - NEXUS_MATCH_RANGE(final_quat.getW(), match_tolerance)); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".orientation.x", final_quat.getX(), match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".orientation.y", final_quat.getY(), match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".orientation.z", final_quat.getZ(), match_tolerance); + queryAppendRangeInclusiveWithTolerance( + query, meta_name + ".orientation.w", final_quat.getW(), match_tolerance); } query.append("link_name", plan_request.link_name); @@ -1555,7 +1535,5 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_metadata( return true; } -#undef NEXUS_MATCH_RANGE - } // namespace motion_planner } // namespace nexus From 5563f3cd4064a1ada1c4899f605544af8ecbcf18 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 11:49:17 -0800 Subject: [PATCH 02/13] Default to warehouse_ros plugin if warehouse plugin isn't set Signed-off-by: methylDragon --- nexus_motion_planner/src/motion_plan_cache.cpp | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index a0bdb20..9ad674b 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -41,17 +41,13 @@ void queryAppendRangeInclusiveWithTolerance( MotionPlanCache::MotionPlanCache(const rclcpp::Node::SharedPtr& node) : node_(node) { - if (!node_->has_parameter("warehouse_plugin")) - { - node_->declare_parameter( - "warehouse_plugin", "warehouse_ros_sqlite::DatabaseConnection"); - } - 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(); } From 03afb8e898fa76ef41507727368769927de1d0ae Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 11:58:02 -0800 Subject: [PATCH 03/13] Return and use init result Signed-off-by: methylDragon --- nexus_motion_planner/src/motion_plan_cache.cpp | 4 ++-- nexus_motion_planner/src/motion_plan_cache.hpp | 2 +- nexus_motion_planner/src/motion_planner_server.cpp | 8 ++++++-- 3 files changed, 9 insertions(+), 5 deletions(-) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index 9ad674b..7e0d3d8 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -52,7 +52,7 @@ MotionPlanCache::MotionPlanCache(const rclcpp::Node::SharedPtr& node) db_ = loader.loadDatabase(); } -void MotionPlanCache::init( +bool MotionPlanCache::init( const std::string& db_path, uint32_t db_port, double exact_match_precision) { RCLCPP_INFO( @@ -62,7 +62,7 @@ void MotionPlanCache::init( exact_match_precision_ = exact_match_precision; db_->setParams(db_path, db_port); - db_->connect(); + return db_->connect(); } // ============================================================================= diff --git a/nexus_motion_planner/src/motion_plan_cache.hpp b/nexus_motion_planner/src/motion_plan_cache.hpp index 4f916ad..e637e35 100644 --- a/nexus_motion_planner/src/motion_plan_cache.hpp +++ b/nexus_motion_planner/src/motion_plan_cache.hpp @@ -88,7 +88,7 @@ class MotionPlanCache // it... explicit MotionPlanCache(const rclcpp::Node::SharedPtr& node); - void init( + bool init( const std::string& db_path = ":memory:", uint32_t db_port = 0, double exact_match_precision = 1e-6); diff --git a/nexus_motion_planner/src/motion_planner_server.cpp b/nexus_motion_planner/src/motion_planner_server.cpp index 58d9208..4f7dc27 100644 --- a/nexus_motion_planner/src/motion_planner_server.cpp +++ b/nexus_motion_planner/src/motion_planner_server.cpp @@ -304,8 +304,12 @@ auto MotionPlannerServer::on_configure(const LifecycleState& /*state*/) if (_cache_mode != PlannerDatabaseMode::Unset) { - _motion_plan_cache->init( - _cache_db_host, _cache_db_port, _cache_exact_match_tolerance); + 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) From 0e84dd4576d070a1ed11d1cdac9d492ca5aedaf7 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 12:13:25 -0800 Subject: [PATCH 04/13] Add todo for catching exceptions Signed-off-by: methylDragon --- nexus_motion_planner/src/motion_planner_server.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/nexus_motion_planner/src/motion_planner_server.cpp b/nexus_motion_planner/src/motion_planner_server.cpp index 4f7dc27..3a26de4 100644 --- a/nexus_motion_planner/src/motion_planner_server.cpp +++ b/nexus_motion_planner/src/motion_planner_server.cpp @@ -12,6 +12,8 @@ // 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) From 6004f96fc39d4b287ab5c142adb1fc220c83a4b8 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 12:56:12 -0800 Subject: [PATCH 05/13] Implement plan fetching with configurable key Signed-off-by: methylDragon --- .../src/motion_plan_cache.cpp | 32 ++++++++-------- .../src/motion_plan_cache.hpp | 37 ++++++++++++++++--- 2 files changed, 46 insertions(+), 23 deletions(-) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index 7e0d3d8..39e0b78 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -74,7 +74,8 @@ 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) + 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); @@ -92,8 +93,7 @@ MotionPlanCache::fetch_all_matching_plans( return {}; } - return coll.queryList( - query, metadata_only, /* sort_by */ "execution_time_s", true); + return coll.queryList(query, metadata_only, sort_by, true); } MessageWithMetadata::ConstPtr @@ -101,14 +101,14 @@ 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) + 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); + plan_request, start_tolerance, goal_tolerance, true, sort_by); if (matching_plans.empty()) { @@ -134,9 +134,7 @@ MotionPlanCache::put_plan( 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 overwrite) + double execution_time_s, double planning_time_s, bool overwrite) { // Check pre-conditions if (!plan.multi_dof_joint_trajectory.points.empty()) @@ -921,8 +919,8 @@ MotionPlanCache::extract_and_append_plan_goal_to_metadata( 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) + const std::vector& waypoints, + double step, double jump_threshold, bool avoid_collisions) { moveit_msgs::srv::GetCartesianPath::Request out; @@ -958,7 +956,8 @@ MotionPlanCache::fetch_all_matching_cartesian_plans( 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) + 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); @@ -977,9 +976,7 @@ MotionPlanCache::fetch_all_matching_cartesian_plans( } query->appendGTE("fraction", min_fraction); - - return coll.queryList( - query, metadata_only, /* sort_by */ "execution_time_s", true); + return coll.queryList(query, metadata_only, sort_by, true); } MessageWithMetadata::ConstPtr @@ -988,14 +985,15 @@ MotionPlanCache::fetch_best_matching_cartesian_plan( 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) + 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); + start_tolerance, goal_tolerance, true, sort_by); if (matching_plans.empty()) { diff --git a/nexus_motion_planner/src/motion_plan_cache.hpp b/nexus_motion_planner/src/motion_plan_cache.hpp index e637e35..89e06ce 100644 --- a/nexus_motion_planner/src/motion_plan_cache.hpp +++ b/nexus_motion_planner/src/motion_plan_cache.hpp @@ -97,6 +97,9 @@ class MotionPlanCache // 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 @@ -106,8 +109,13 @@ class MotionPlanCache 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); + 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 @@ -115,7 +123,10 @@ class MotionPlanCache 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); + double start_tolerance, + double goal_tolerance, + bool metadata_only = false, + const std::string& sort_by = "execution_time_s"); bool put_plan( const moveit::planning_interface::MoveGroupInterface& move_group, @@ -154,14 +165,20 @@ class MotionPlanCache // 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); + 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 @@ -172,8 +189,13 @@ class MotionPlanCache 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); + 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 @@ -182,7 +204,10 @@ class MotionPlanCache 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); + double start_tolerance, + double goal_tolerance, + bool metadata_only = false, + const std::string& sort_by = "execution_time_s"); bool put_cartesian_plan( const moveit::planning_interface::MoveGroupInterface& move_group, From ccbf91cd9f98e626bd1ba4a535b5b2aff10eba0c Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 13:25:26 -0800 Subject: [PATCH 06/13] Add comments for exact match tolerance Signed-off-by: methylDragon --- nexus_motion_planner/src/motion_planner_server.cpp | 1 + nexus_motion_planner/src/motion_planner_server.hpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/nexus_motion_planner/src/motion_planner_server.cpp b/nexus_motion_planner/src/motion_planner_server.cpp index 3a26de4..2c3ce5e 100644 --- a/nexus_motion_planner/src/motion_planner_server.cpp +++ b/nexus_motion_planner/src/motion_planner_server.cpp @@ -247,6 +247,7 @@ MotionPlannerServer::MotionPlannerServer(const rclcpp::NodeOptions& options) "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( diff --git a/nexus_motion_planner/src/motion_planner_server.hpp b/nexus_motion_planner/src/motion_planner_server.hpp index 9032bf4..7451d7a 100644 --- a/nexus_motion_planner/src/motion_planner_server.hpp +++ b/nexus_motion_planner/src/motion_planner_server.hpp @@ -127,7 +127,7 @@ class MotionPlannerServer : public rclcpp_lifecycle::LifecycleNode std::string _cache_db_plugin; std::string _cache_db_host; int _cache_db_port; - double _cache_exact_match_tolerance; + double _cache_exact_match_tolerance; // for floating point comparison double _cache_start_match_tolerance; double _cache_goal_match_tolerance; From 06cdcf90e5d44791f973f4ab3d900cf203089d87 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 14:55:52 -0800 Subject: [PATCH 07/13] Slightly refactor put plan Signed-off-by: methylDragon --- .../src/motion_plan_cache.cpp | 100 +++++++++--------- 1 file changed, 48 insertions(+), 52 deletions(-) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index 39e0b78..10d2188 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -141,14 +141,14 @@ MotionPlanCache::put_plan( { RCLCPP_ERROR( node_->get_logger(), - "Skipping insert: Multi-DOF trajectory plans are not supported."); + "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 insert: Frame IDs cannot be empty."); + node_->get_logger(), "Skipping plan insert: Frame IDs cannot be empty."); return false; } if (plan_request.workspace_parameters.header.frame_id != @@ -156,7 +156,7 @@ MotionPlanCache::put_plan( { RCLCPP_ERROR( node_->get_logger(), - "Skipping insert: " + "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()); @@ -166,8 +166,7 @@ MotionPlanCache::put_plan( auto coll = db_->openCollection( "move_group_plan_cache", move_group_namespace); - // If start and goal are "exact" match, AND the candidate plan is better, - // overwrite. + // 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( @@ -179,27 +178,25 @@ MotionPlanCache::put_plan( { RCLCPP_ERROR( node_->get_logger(), - "Skipping insert: Could not construct overwrite query."); + "Skipping plan insert: Could not construct lookup query."); return false; } - auto exact_matches = coll.queryList(exact_query, /* metadata_only */ true); - double best_execution_time_seen = std::numeric_limits::infinity(); + 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()) { - for (auto& match : exact_matches) - { - double match_execution_time_s = - match->lookupDouble("execution_time_s"); - if (match_execution_time_s < best_execution_time_seen) - { - best_execution_time_seen = match_execution_time_s; - } + best_execution_time = exact_matches.at(0)->lookupDouble("execution_time_s"); - if (match_execution_time_s > execution_time_s) + // Delete "worse" plans if overwrite requested. + if (overwrite) + { + for (auto& match : exact_matches) { - // If we found any "exact" matches that are worse, delete them. - if (overwrite) + 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( @@ -217,7 +214,7 @@ MotionPlanCache::put_plan( } // Insert if candidate is best seen. - if (execution_time_s < best_execution_time_seen) + if (execution_time_s < best_execution_time) { Metadata::Ptr insert_metadata = coll.createMetadata(); @@ -232,7 +229,7 @@ MotionPlanCache::put_plan( { RCLCPP_ERROR( node_->get_logger(), - "Skipping insert: Could not construct insert metadata."); + "Skipping plan insert: Could not construct insert metadata."); return false; } @@ -240,7 +237,7 @@ MotionPlanCache::put_plan( 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_seen); + execution_time_s, best_execution_time); coll.insert(plan, insert_metadata); return true; @@ -248,9 +245,9 @@ MotionPlanCache::put_plan( RCLCPP_INFO( node_->get_logger(), - "Skipping insert: New plan execution_time (%es) " + "Skipping plan insert: New plan execution_time (%es) " "is worse than best plan's execution_time (%es)", - execution_time_s, best_execution_time_seen); + execution_time_s, best_execution_time); return false; } @@ -971,7 +968,8 @@ MotionPlanCache::fetch_all_matching_cartesian_plans( if (!start_ok || !goal_ok) { - RCLCPP_ERROR(node_->get_logger(), "Could not construct plan query."); + RCLCPP_ERROR( + node_->get_logger(), "Could not construct cartesian plan query."); return {}; } @@ -997,7 +995,7 @@ MotionPlanCache::fetch_best_matching_cartesian_plan( if (matching_plans.empty()) { - RCLCPP_INFO(node_->get_logger(), "No matching plans found."); + RCLCPP_INFO(node_->get_logger(), "No matching cartesian plans found."); return nullptr; } @@ -1029,61 +1027,59 @@ MotionPlanCache::put_cartesian_plan( { RCLCPP_ERROR( node_->get_logger(), - "Skipping insert: Multi-DOF trajectory plans are not supported."); + "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 insert: Frame IDs cannot be empty."); + 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); - // If start and goal are "exact" match, AND the candidate plan is better, - // overwrite. + // 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 insert: Could not construct overwrite query."); + "Skipping cartesian plan insert: Could not construct lookup query."); return false; } - auto exact_matches = coll.queryList(exact_query, /* metadata_only */ true); - double best_execution_time_seen = std::numeric_limits::infinity(); + 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()) { - for (auto& match : exact_matches) - { - double match_execution_time_s = - match->lookupDouble("execution_time_s"); - if (match_execution_time_s < best_execution_time_seen) - { - best_execution_time_seen = match_execution_time_s; - } + best_execution_time = exact_matches.at(0)->lookupDouble("execution_time_s"); - if (match_execution_time_s > execution_time_s) + // Delete "worse" plans if overwrite requested. + if (overwrite) + { + for (auto& match : exact_matches) { - // If we found any "exact" matches that are worse, delete them. - if (overwrite) + 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): " + "Overwriting cartesian plan (id: %d): " "execution_time (%es) > new plan's execution_time (%es)", delete_id, match_execution_time_s, execution_time_s); @@ -1096,7 +1092,7 @@ MotionPlanCache::put_cartesian_plan( } // Insert if candidate is best seen. - if (execution_time_s < best_execution_time_seen) + if (execution_time_s < best_execution_time) { Metadata::Ptr insert_metadata = coll.createMetadata(); @@ -1114,15 +1110,15 @@ MotionPlanCache::put_cartesian_plan( { RCLCPP_ERROR( node_->get_logger(), - "Skipping insert: Could not construct insert metadata."); + "Skipping cartesian plan insert: Could not construct insert metadata."); return false; } RCLCPP_INFO( node_->get_logger(), - "Inserting plan: New plan execution_time (%es) " + "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_seen, fraction); + execution_time_s, best_execution_time, fraction); coll.insert(plan, insert_metadata); return true; @@ -1130,9 +1126,9 @@ MotionPlanCache::put_cartesian_plan( RCLCPP_INFO( node_->get_logger(), - "Skipping insert: New plan execution_time (%es) " + "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_seen, fraction); + execution_time_s, best_execution_time, fraction); return false; } From d1847baa85525f2c4bdabcf5eed631246e4c1acf Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 14:59:29 -0800 Subject: [PATCH 08/13] Rename overwrite to delete_worse_plans Signed-off-by: methylDragon --- .../src/motion_plan_cache.cpp | 10 ++++------ .../src/motion_plan_cache.hpp | 19 +++++++++++++++++-- 2 files changed, 21 insertions(+), 8 deletions(-) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index 10d2188..8470182 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -134,7 +134,7 @@ MotionPlanCache::put_plan( 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 overwrite) + double execution_time_s, double planning_time_s, bool delete_worse_plans) { // Check pre-conditions if (!plan.multi_dof_joint_trajectory.points.empty()) @@ -190,8 +190,7 @@ MotionPlanCache::put_plan( { best_execution_time = exact_matches.at(0)->lookupDouble("execution_time_s"); - // Delete "worse" plans if overwrite requested. - if (overwrite) + if (delete_worse_plans) { for (auto& match : exact_matches) { @@ -1020,7 +1019,7 @@ MotionPlanCache::put_cartesian_plan( double execution_time_s, double planning_time_s, double fraction, - bool overwrite) + bool delete_worse_plans) { // Check pre-conditions if (!plan.multi_dof_joint_trajectory.points.empty()) @@ -1068,8 +1067,7 @@ MotionPlanCache::put_cartesian_plan( { best_execution_time = exact_matches.at(0)->lookupDouble("execution_time_s"); - // Delete "worse" plans if overwrite requested. - if (overwrite) + if (delete_worse_plans) { for (auto& match : exact_matches) { diff --git a/nexus_motion_planner/src/motion_plan_cache.hpp b/nexus_motion_planner/src/motion_plan_cache.hpp index 89e06ce..fc7bbff 100644 --- a/nexus_motion_planner/src/motion_plan_cache.hpp +++ b/nexus_motion_planner/src/motion_plan_cache.hpp @@ -128,6 +128,13 @@ class MotionPlanCache 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, @@ -135,7 +142,7 @@ class MotionPlanCache const moveit_msgs::msg::RobotTrajectory& plan, double execution_time_s, double planning_time_s, - bool overwrite = true); + bool delete_worse_plans = true); // QUERY CONSTRUCTION bool extract_and_append_plan_start_to_query( @@ -209,6 +216,14 @@ class MotionPlanCache 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, @@ -217,7 +232,7 @@ class MotionPlanCache double execution_time_s, double planning_time_s, double fraction, - bool overwrite = true); + bool delete_worse_plans = true); // QUERY CONSTRUCTION bool extract_and_append_cartesian_plan_start_to_query( From 6e5b9634d55f0b5ea8e8a24018a1f5afeff55f91 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 15:58:51 -0800 Subject: [PATCH 09/13] Split out motion plan cache into its own library Signed-off-by: methylDragon --- nexus_motion_planner/CMakeLists.txt | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/nexus_motion_planner/CMakeLists.txt b/nexus_motion_planner/CMakeLists.txt index e9003bf..ca94c1e 100644 --- a/nexus_motion_planner/CMakeLists.txt +++ b/nexus_motion_planner/CMakeLists.txt @@ -43,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 src/motion_plan_cache.cpp) +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) From 636b4d504da1adc6e46dc8dadc13d8b5603bbde8 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 19:32:26 -0800 Subject: [PATCH 10/13] Sort constraints for reduced cardinality Signed-off-by: methylDragon --- .../src/motion_plan_cache.cpp | 46 +++++++++++++++++++ 1 file changed, 46 insertions(+) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index 8470182..2a77d7e 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -30,6 +30,8 @@ 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 queryAppendRangeInclusiveWithTolerance( Query& query, const std::string& name, double center, double tolerance) @@ -38,6 +40,42 @@ void queryAppendRangeInclusiveWithTolerance( 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) { @@ -417,6 +455,10 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( { orientation_constraints.push_back(orientation_constraint); } + + // Also sort for even less cardinality. + sort_constraints( + joint_constraints, position_constraints, orientation_constraints); } // Joint constraints @@ -742,6 +784,10 @@ MotionPlanCache::extract_and_append_plan_goal_to_metadata( { orientation_constraints.push_back(orientation_constraint); } + + // Also sort for even less cardinality. + sort_constraints( + joint_constraints, position_constraints, orientation_constraints); } // Joint constraints From 5ea5ad5909e10c38336ce6463163420e885e13a3 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 19:42:22 -0800 Subject: [PATCH 11/13] Rename util function Signed-off-by: methylDragon --- .../src/motion_plan_cache.cpp | 54 +++++++++---------- 1 file changed, 27 insertions(+), 27 deletions(-) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index 2a77d7e..b3655cb 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -33,7 +33,7 @@ using warehouse_ros::Query; // Utils ======================================================================= // Append a range inclusive query with some tolerance about some center value. -void queryAppendRangeInclusiveWithTolerance( +void query_append_range_inclusive_with_tolerance( Query& query, const std::string& name, double center, double tolerance) { query.appendRangeInclusive( @@ -369,7 +369,7 @@ MotionPlanCache::extract_and_append_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), current_state_msg.joint_state.name.at(i)); - queryAppendRangeInclusiveWithTolerance( + 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); } @@ -383,7 +383,7 @@ MotionPlanCache::extract_and_append_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), plan_request.start_state.joint_state.name.at(i)); - queryAppendRangeInclusiveWithTolerance( + 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); } @@ -427,13 +427,13 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( // auto original = *query; // Copy not supported. - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, "max_velocity_scaling_factor", plan_request.max_velocity_scaling_factor, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, "max_acceleration_scaling_factor", plan_request.max_acceleration_scaling_factor, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, "max_cartesian_speed", plan_request.max_cartesian_speed, match_tolerance); @@ -469,7 +469,7 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( "goal_constraints.joint_constraints_" + std::to_string(joint_idx++); query.append(meta_name + ".joint_name", constraint.joint_name); - queryAppendRangeInclusiveWithTolerance( + 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); @@ -527,13 +527,13 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( query.append(meta_name + ".link_name", constraint.link_name); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".target_point_offset.x", x_offset + constraint.target_point_offset.x, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".target_point_offset.y", y_offset + constraint.target_point_offset.y, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".target_point_offset.z", z_offset + constraint.target_point_offset.z, match_tolerance); } @@ -609,16 +609,16 @@ MotionPlanCache::extract_and_append_plan_goal_to_query( auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; final_quat.normalize(); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".target_point_offset.x", final_quat.getX(), match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".target_point_offset.y", final_quat.getY(), match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".target_point_offset.z", final_quat.getZ(), match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".target_point_offset.w", final_quat.getW(), match_tolerance); } @@ -1233,7 +1233,7 @@ MotionPlanCache::extract_and_append_cartesian_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), current_state_msg.joint_state.name.at(i)); - queryAppendRangeInclusiveWithTolerance( + 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); } @@ -1247,7 +1247,7 @@ MotionPlanCache::extract_and_append_cartesian_plan_start_to_query( query.append( "start_state.joint_state.name_" + std::to_string(i), plan_request.start_state.joint_state.name.at(i)); - queryAppendRangeInclusiveWithTolerance( + 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); } @@ -1282,15 +1282,15 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( // auto original = *metadata; // Copy not supported. - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, "max_velocity_scaling_factor", plan_request.max_velocity_scaling_factor, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, "max_acceleration_scaling_factor", plan_request.max_acceleration_scaling_factor, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, "max_step", plan_request.max_step, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, "jump_threshold", plan_request.jump_threshold, match_tolerance); // Waypoints @@ -1346,13 +1346,13 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( // Apply offsets // Position - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".position.x", x_offset + waypoint.position.x, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".position.y", y_offset+ waypoint.position.y, match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".position.z", z_offset+waypoint.position.z, match_tolerance); @@ -1367,13 +1367,13 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( auto final_quat = tf2_quat_goal_offset * tf2_quat_frame_offset; final_quat.normalize(); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".orientation.x", final_quat.getX(), match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".orientation.y", final_quat.getY(), match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".orientation.z", final_quat.getZ(), match_tolerance); - queryAppendRangeInclusiveWithTolerance( + query_append_range_inclusive_with_tolerance( query, meta_name + ".orientation.w", final_quat.getW(), match_tolerance); } From bbc07cec581f5b127ec7f86227da69b078994a38 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 20 Nov 2023 19:55:09 -0800 Subject: [PATCH 12/13] Add todo for is_diff Signed-off-by: methylDragon --- .../src/motion_plan_cache.cpp | 28 +++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index b3655cb..b2e8096 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -351,6 +351,13 @@ MotionPlanCache::extract_and_append_plan_start_to_query( // 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) { @@ -686,6 +693,13 @@ MotionPlanCache::extract_and_append_plan_start_to_metadata( // 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) { @@ -1215,6 +1229,13 @@ MotionPlanCache::extract_and_append_cartesian_plan_start_to_query( // 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) { @@ -1418,6 +1439,13 @@ MotionPlanCache::extract_and_append_cartesian_plan_start_to_metadata( // 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) { From 1af731b8a5faa20505fd0502b8f5ec39b8ca4b2a Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 27 Nov 2023 16:46:42 -0600 Subject: [PATCH 13/13] Add unit tests for motion plan cache (#28) * Add count methods Signed-off-by: methylDragon * Enable shared from this for cache class Signed-off-by: methylDragon * Add unit test build rules Signed-off-by: methylDragon * Add tests for motion plan cache (but not cartesian) Signed-off-by: methylDragon * Fix bugs in cartesian caching Signed-off-by: methylDragon * Add tests for cartesian plan cache Signed-off-by: methylDragon * Exit if a test fails Signed-off-by: methylDragon * Remove gtest import Signed-off-by: methylDragon * Remove enable_shared_from_this Signed-off-by: methylDragon * Only check for failure Signed-off-by: methylDragon * Test half in-tolerance Signed-off-by: methylDragon * Test different robot cache Signed-off-by: methylDragon * Add force_cache_mode_execute_read_only (#29) * Add force_cache_mode_execute_read_only Signed-off-by: methylDragon * Add force_cache_mode_execute_read_only input port Signed-off-by: methylDragon --------- Signed-off-by: methylDragon --------- Signed-off-by: methylDragon --- .../src/capabilities/plan_motion.cpp | 11 + .../src/capabilities/plan_motion.hpp | 3 + nexus_motion_planner/CMakeLists.txt | 26 +- nexus_motion_planner/package.xml | 6 + .../src/motion_plan_cache.cpp | 46 +- .../src/motion_plan_cache.hpp | 7 +- .../src/motion_planner_server.cpp | 6 +- .../src/test_motion_plan_cache.cpp | 1317 +++++++++++++++++ .../test/test_motion_plan_cache.py | 148 ++ .../srv/GetMotionPlan.srv | 5 + nexus_tree_nodes.xml | 1 + 11 files changed, 1552 insertions(+), 24 deletions(-) create mode 100644 nexus_motion_planner/src/test_motion_plan_cache.cpp create mode 100755 nexus_motion_planner/test/test_motion_plan_cache.py diff --git a/nexus_capabilities/src/capabilities/plan_motion.cpp b/nexus_capabilities/src/capabilities/plan_motion.cpp index 4d83079..b762a93 100644 --- a/nexus_capabilities/src/capabilities/plan_motion.cpp +++ b/nexus_capabilities/src/capabilities/plan_motion.cpp @@ -120,6 +120,17 @@ make_request() req->max_velocity_scaling_factor = scale_speed; req->max_acceleration_scaling_factor = scale_speed; + auto maybe_read_only = + this->getInput("force_cache_mode_execute_read_only"); + if (maybe_read_only.has_value()) + { + req->force_cache_mode_execute_read_only = maybe_read_only.value(); + } + else + { + req->force_cache_mode_execute_read_only = false; + } + RCLCPP_DEBUG_STREAM(this->_logger, "planning to " << req->goal_pose.pose << " at frame " << req->goal_pose.header.frame_id << " with cartesian " << req->cartesian << "and scaled speed of " << diff --git a/nexus_capabilities/src/capabilities/plan_motion.hpp b/nexus_capabilities/src/capabilities/plan_motion.hpp index ce72073..57dcc58 100644 --- a/nexus_capabilities/src/capabilities/plan_motion.hpp +++ b/nexus_capabilities/src/capabilities/plan_motion.hpp @@ -66,6 +66,9 @@ public: static BT::PortsList providedPorts() BT::InputPort>( "start_constraints", "OPTIONAL. If provided the the joint_constraints are used as the start condition. Else, the current state of the robot will be used as the start."), + BT::InputPort( + "force_cache_mode_execute_read_only", + "OPTIONAL. Set true to force cache mode to ExecuteReadOnly for this request."), BT::OutputPort( "result", "The resulting trajectory.")}; } diff --git a/nexus_motion_planner/CMakeLists.txt b/nexus_motion_planner/CMakeLists.txt index ca94c1e..bcb51ee 100644 --- a/nexus_motion_planner/CMakeLists.txt +++ b/nexus_motion_planner/CMakeLists.txt @@ -28,12 +28,17 @@ set (motion_planner_server_dependencies rclcpp rclcpp_action rclcpp_lifecycle - warehouse_ros - warehouse_ros_sqlite tf2 tf2_ros ) +set (motion_plan_cache_dependencies + moveit_ros_planning_interface + rclcpp + warehouse_ros + warehouse_ros_sqlite +) + set (test_request_dependencies moveit_msgs nexus_endpoints @@ -48,7 +53,7 @@ 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}) +ament_target_dependencies(${MOTION_PLAN_CACHE_LIBRARY_NAME} ${motion_plan_cache_dependencies}) # Server executable add_executable(${EXECUTABLE_NAME} src/main.cpp src/motion_planner_server.cpp) @@ -72,6 +77,7 @@ install( ) if(BUILD_TESTING) + find_package(ament_cmake_pytest REQUIRED) find_package(ament_cmake_uncrustify REQUIRED) find_package(launch_testing_ament_cmake REQUIRED) find_package(rmf_utils REQUIRED) @@ -80,6 +86,14 @@ if(BUILD_TESTING) NAMES "rmf_code_style.cfg" PATHS "${rmf_utils_DIR}/../../../../share/rmf_utils/") + add_executable(test_motion_plan_cache src/test_motion_plan_cache.cpp) + target_link_libraries(test_motion_plan_cache ${MOTION_PLAN_CACHE_LIBRARY_NAME}) + + install(TARGETS + test_motion_plan_cache + RUNTIME DESTINATION lib/${PROJECT_NAME} + ) + ament_uncrustify( ARGN include src test CONFIG_FILE ${uncrustify_config_file} @@ -87,6 +101,10 @@ if(BUILD_TESTING) LANGUAGE CPP ) + ament_add_pytest_test(test_motion_plan_cache_py "test/test_motion_plan_cache.py" + WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" + ) + # TODO(YV): Fix these tests. # add_launch_test( # test/test_request.test.py @@ -94,5 +112,5 @@ if(BUILD_TESTING) # ) endif() -ament_export_dependencies(${motion_planner_server_dependencies}) +ament_export_dependencies(${motion_planner_server_dependencies} ${motion_plan_cache_dependencies}) ament_package() diff --git a/nexus_motion_planner/package.xml b/nexus_motion_planner/package.xml index d23de1d..57e2739 100644 --- a/nexus_motion_planner/package.xml +++ b/nexus_motion_planner/package.xml @@ -28,8 +28,14 @@ abb_irb1300_10_115_moveit_config abb_irb1300_support + ament_cmake_pytest ament_cmake_uncrustify + launch_pytest launch_testing_ament_cmake + + moveit_configs_utils + moveit_resources + python3-pytest rmf_utils diff --git a/nexus_motion_planner/src/motion_plan_cache.cpp b/nexus_motion_planner/src/motion_plan_cache.cpp index b2e8096..bee939f 100644 --- a/nexus_motion_planner/src/motion_plan_cache.cpp +++ b/nexus_motion_planner/src/motion_plan_cache.cpp @@ -103,6 +103,22 @@ bool MotionPlanCache::init( return db_->connect(); } +unsigned +MotionPlanCache::count_plans(const std::string& move_group_namespace) +{ + auto coll = db_->openCollection( + "move_group_plan_cache", move_group_namespace); + return coll.count(); +} + +unsigned +MotionPlanCache::count_cartesian_plans(const std::string& move_group_namespace) +{ + auto coll = db_->openCollection( + "move_group_cartesian_plan_cache", move_group_namespace); + return coll.count(); +} + // ============================================================================= // MOTION PLAN CACHING // ============================================================================= @@ -204,7 +220,7 @@ MotionPlanCache::put_plan( auto coll = db_->openCollection( "move_group_plan_cache", move_group_namespace); - // Pull out "exact" matching plans in cache. + // Pull out plans "exactly" keyed by request in cache. Query::Ptr exact_query = coll.createQuery(); bool start_query_ok = this->extract_and_append_plan_start_to_query( @@ -1059,7 +1075,7 @@ MotionPlanCache::fetch_best_matching_cartesian_plan( } auto coll = db_->openCollection( - "move_group_plan_cache", move_group_namespace); + "move_group_cartesian_plan_cache", move_group_namespace); // Best plan is at first index, since the lookup query was sorted by // execution_time. @@ -1095,15 +1111,14 @@ MotionPlanCache::put_cartesian_plan( { RCLCPP_ERROR( node_->get_logger(), - "Skipping cartesian plan insert: " - "Frame IDs cannot be empty."); + "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. + // Pull out plans "exactly" keyed by request in cache. Query::Ptr exact_query = coll.createQuery(); bool start_query_ok = this->extract_and_append_cartesian_plan_start_to_query( @@ -1287,10 +1302,10 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( 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()) + 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."); @@ -1372,10 +1387,10 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( 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); + 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); + z_offset + waypoint.position.z, match_tolerance); // Orientation tf2::Quaternion tf2_quat_goal_offset( @@ -1399,6 +1414,7 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_query( } query.append("link_name", plan_request.link_name); + query.append("header.frame_id", base_frame); return true; } @@ -1494,10 +1510,10 @@ MotionPlanCache::extract_and_append_cartesian_plan_goal_to_metadata( 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()) + 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."); diff --git a/nexus_motion_planner/src/motion_plan_cache.hpp b/nexus_motion_planner/src/motion_plan_cache.hpp index fc7bbff..fc6143c 100644 --- a/nexus_motion_planner/src/motion_plan_cache.hpp +++ b/nexus_motion_planner/src/motion_plan_cache.hpp @@ -37,9 +37,6 @@ #include #include -// NEXUS messages -#include - namespace nexus { namespace motion_planner { @@ -93,6 +90,10 @@ class MotionPlanCache uint32_t db_port = 0, double exact_match_precision = 1e-6); + unsigned count_plans(const std::string& move_group_namespace); + + unsigned count_cartesian_plans(const std::string& move_group_namespace); + // =========================================================================== // MOTION PLAN CACHING // =========================================================================== diff --git a/nexus_motion_planner/src/motion_planner_server.cpp b/nexus_motion_planner/src/motion_planner_server.cpp index 2c3ce5e..d24b442 100644 --- a/nexus_motion_planner/src/motion_planner_server.cpp +++ b/nexus_motion_planner/src/motion_planner_server.cpp @@ -615,7 +615,8 @@ void MotionPlannerServer::plan_with_move_group( _collision_aware_cartesian_path); // Fetch if in execute mode. - if (cache_mode_is_execute(_cache_mode)) + if (cache_mode_is_execute(_cache_mode) + || req.force_cache_mode_execute_read_only) { auto fetch_start = this->now(); auto fetched_cartesian_plan = @@ -640,7 +641,8 @@ void MotionPlannerServer::plan_with_move_group( fetched_cartesian_plan->lookupDouble("planning_time_s")); } // Fail if ReadOnly mode and no cached cartesian plan was fetched. - else if (_cache_mode == PlannerDatabaseMode::ExecuteReadOnly) + else if (_cache_mode == PlannerDatabaseMode::ExecuteReadOnly + || req.force_cache_mode_execute_read_only) { RCLCPP_ERROR( this->get_logger(), diff --git a/nexus_motion_planner/src/test_motion_plan_cache.cpp b/nexus_motion_planner/src/test_motion_plan_cache.cpp new file mode 100644 index 0000000..64e71c7 --- /dev/null +++ b/nexus_motion_planner/src/test_motion_plan_cache.cpp @@ -0,0 +1,1317 @@ +// Copyright 2023 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 "moveit/robot_state/conversions.h" +#include "moveit/robot_state/robot_state.h" +#include "motion_plan_cache.hpp" + +#include + +using moveit::planning_interface::MoveGroupInterface; +using nexus::motion_planner::MotionPlanCache; + +const std::string g_robot_name = "panda"; +const std::string g_robot_frame = "world"; + +// UTILS ======================================================================= +// Utility function to emit a pass or fail statement. +void check_and_emit( + bool predicate, const std::string& prefix, const std::string& label) +{ + if (predicate) + { + std::cout << "[PASS] " << prefix << ": " << label << std::endl; + } + else + { + std::cout << "[FAIL] " << prefix << ": " << label << std::endl; + exit(1); + } +} + +moveit_msgs::msg::RobotTrajectory get_dummy_panda_plan() +{ + static moveit_msgs::msg::RobotTrajectory out = []() + { + moveit_msgs::msg::RobotTrajectory plan; + + auto traj = &plan.joint_trajectory; + traj->header.frame_id = g_robot_frame; + + traj->joint_names.push_back(g_robot_name + "_joint1"); + traj->joint_names.push_back(g_robot_name + "_joint2"); + traj->joint_names.push_back(g_robot_name + "_joint3"); + traj->joint_names.push_back(g_robot_name + "_joint4"); + traj->joint_names.push_back(g_robot_name + "_joint5"); + traj->joint_names.push_back(g_robot_name + "_joint6"); + traj->joint_names.push_back(g_robot_name + "_joint7"); + + traj->points.emplace_back(); + traj->points.at(0).positions = {0, 0, 0, 0, 0, 0}; + traj->points.at(0).velocities = {0, 0, 0, 0, 0, 0}; + traj->points.at(0).accelerations = {0, 0, 0, 0, 0, 0}; + traj->points.at(0).time_from_start.sec = 999999; + + return plan; + }(); + return out; +} + +std::vector get_dummy_waypoints() +{ + static std::vector out = []() + { + std::vector waypoints; + for (size_t i = 0; i < 3; i++) + { + waypoints.emplace_back(); + waypoints.at(i).position.x = i; + waypoints.at(i).position.y = i; + waypoints.at(i).position.z = i; + waypoints.at(i).orientation.w = i; + waypoints.at(i).orientation.x = i + 0.1; + waypoints.at(i).orientation.y = i + 0.1; + waypoints.at(i).orientation.z = i + 0.1; + } + return waypoints; + }(); + return out; +} + + +void test_motion_plans( + std::shared_ptr move_group, + std::shared_ptr cache) +{ + // Setup ===================================================================== + // All variants are copies. + + /// MotionPlanRequest + + // Plain start + moveit_msgs::msg::MotionPlanRequest plan_req; + move_group->constructMotionPlanRequest(plan_req); + plan_req.workspace_parameters.header.frame_id = g_robot_frame; + plan_req.workspace_parameters.max_corner.x = 10; + plan_req.workspace_parameters.max_corner.y = 10; + plan_req.workspace_parameters.max_corner.z = 10; + plan_req.workspace_parameters.min_corner.x = -10; + plan_req.workspace_parameters.min_corner.y = -10; + plan_req.workspace_parameters.min_corner.z = -10; + plan_req.start_state.multi_dof_joint_state.joint_names.clear(); + plan_req.start_state.multi_dof_joint_state.transforms.clear(); + plan_req.start_state.multi_dof_joint_state.twist.clear(); + plan_req.start_state.multi_dof_joint_state.wrench.clear(); + + // Empty frame start + moveit_msgs::msg::MotionPlanRequest empty_frame_plan_req = plan_req; + empty_frame_plan_req.workspace_parameters.header.frame_id = ""; + + // is_diff = true + auto is_diff_plan_req = plan_req; + is_diff_plan_req.start_state.is_diff = true; + is_diff_plan_req.start_state.joint_state.header.frame_id = ""; + is_diff_plan_req.start_state.joint_state.name.clear(); + is_diff_plan_req.start_state.joint_state.position.clear(); + is_diff_plan_req.start_state.joint_state.velocity.clear(); + is_diff_plan_req.start_state.joint_state.effort.clear(); + + // Something close enough (mod 0.1 away) + auto close_matching_plan_req = plan_req; + close_matching_plan_req.workspace_parameters.max_corner.x += 0.05; + close_matching_plan_req.workspace_parameters.min_corner.x -= 0.05; + close_matching_plan_req.start_state.joint_state.position.at(0) -= 0.05; + close_matching_plan_req.start_state.joint_state.position.at(1) += 0.05; + close_matching_plan_req.start_state.joint_state.position.at(2) -= 0.05; + close_matching_plan_req.goal_constraints + .at(0).joint_constraints.at(0).position -= 0.05; + close_matching_plan_req.goal_constraints + .at(0).joint_constraints.at(1).position += 0.05; + close_matching_plan_req.goal_constraints + .at(0).joint_constraints.at(2).position -= 0.05; + + // Close with swapped constraints (mod 0.1 away) + auto swapped_close_matching_plan_req = close_matching_plan_req; + std::swap( + swapped_close_matching_plan_req.goal_constraints.at( + 0).joint_constraints.at(0), + swapped_close_matching_plan_req.goal_constraints.at( + 0).joint_constraints.at(1)); + + // Smaller workspace start + auto smaller_workspace_plan_req = plan_req; + smaller_workspace_plan_req.workspace_parameters.max_corner.x = 1; + smaller_workspace_plan_req.workspace_parameters.max_corner.y = 1; + smaller_workspace_plan_req.workspace_parameters.max_corner.z = 1; + smaller_workspace_plan_req.workspace_parameters.min_corner.x = -1; + smaller_workspace_plan_req.workspace_parameters.min_corner.y = -1; + smaller_workspace_plan_req.workspace_parameters.min_corner.z = -1; + + // Larger workspace start + auto larger_workspace_plan_req = plan_req; + larger_workspace_plan_req.workspace_parameters.max_corner.x = 50; + larger_workspace_plan_req.workspace_parameters.max_corner.y = 50; + larger_workspace_plan_req.workspace_parameters.max_corner.z = 50; + larger_workspace_plan_req.workspace_parameters.min_corner.x = -50; + larger_workspace_plan_req.workspace_parameters.min_corner.y = -50; + larger_workspace_plan_req.workspace_parameters.min_corner.z = -50; + + // Different + auto different_plan_req = plan_req; + different_plan_req.workspace_parameters.max_corner.x += 1.05; + different_plan_req.workspace_parameters.min_corner.x -= 2.05; + different_plan_req.start_state.joint_state.position.at(0) -= 3.05; + different_plan_req.start_state.joint_state.position.at(1) += 4.05; + different_plan_req.start_state.joint_state.position.at(2) -= 5.05; + different_plan_req.goal_constraints + .at(0).joint_constraints.at(0).position -= 6.05; + different_plan_req.goal_constraints + .at(0).joint_constraints.at(1).position += 7.05; + different_plan_req.goal_constraints + .at(0).joint_constraints.at(2).position -= 8.05; + + /// RobotTrajectory + + // Plan + auto plan = get_dummy_panda_plan(); + + // Plan with no frame_id in its trajectory header + auto empty_frame_plan = plan; + empty_frame_plan.joint_trajectory.header.frame_id = ""; + + auto different_plan = plan; + different_plan.joint_trajectory.points.at(0).positions.at(0) = 999; + different_plan.joint_trajectory.points.at(0).positions.at(1) = 999; + different_plan.joint_trajectory.points.at(0).positions.at(2) = 999; + + // Test Utils + + std::string prefix; + + // Checks ==================================================================== + + // Initially empty + prefix = "test_motion_plans.empty"; + + check_and_emit( + cache->count_plans(g_robot_name) == 0, + prefix, "Plan cache initially empty"); + + check_and_emit( + cache->fetch_all_matching_plans( + *move_group, g_robot_name, plan_req, 999, 999).empty(), + prefix, "Fetch all plans on empty cache returns empty"); + + check_and_emit( + cache->fetch_best_matching_plan( + *move_group, g_robot_name, plan_req, 999, 999) == nullptr, + prefix, "Fetch best plan on empty cache returns nullptr"); + + // Put plan empty frame + // + // Plan must have frame in joint trajectory, expect put fail + prefix = "test_motion_plans.put_plan_empty_frame"; + double execution_time = 999; + double planning_time = 999; + + check_and_emit( + !cache->put_plan( + *move_group, g_robot_name, plan_req, empty_frame_plan, + execution_time, planning_time, false), + prefix, "Put empty frame plan, no delete_worse_plans, not ok"); + + check_and_emit( + cache->count_plans(g_robot_name) == 0, prefix, "No plans in cache"); + + // Put plan req empty frame + // + // Plan request must have frame in workspace, expect put fail + prefix = "test_motion_plans.put_plan_req_empty_frame"; + execution_time = 999; + planning_time = 999; + + check_and_emit( + !cache->put_plan( + *move_group, g_robot_name, empty_frame_plan_req, plan, + execution_time, planning_time, false), + prefix, "Put empty frame req plan, no delete_worse_plans, not ok"); + + check_and_emit( + cache->count_plans(g_robot_name) == 0, prefix, "No plans in cache"); + + // Put first, no delete_worse_plans + prefix = "test_motion_plans.put_first"; + execution_time = 999; + planning_time = 999; + + check_and_emit( + cache->put_plan( + *move_group, g_robot_name, plan_req, plan, + execution_time, planning_time, false), + prefix, "Put first valid plan, no delete_worse_plans, ok"); + + check_and_emit( + cache->count_plans(g_robot_name) == 1, prefix, "One plan in cache"); + + // Fetch matching, no tolerance + // + // Exact key match should have cache hit + prefix = "test_motion_plans.put_first.fetch_matching_no_tolerance"; + + auto fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, plan_req, 0, 0); + + auto fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, plan_req, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + // Fetch with is_diff + // + // is_diff key should be equivalent to exact match if robot state did not + // change, hence should have cache hit + prefix = "test_motion_plans.put_first.fetch_is_diff_no_tolerance"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, is_diff_plan_req, 0, 0); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, is_diff_plan_req, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + // Fetch non-matching, out of tolerance + // + // Non-matching key should not have cache hit + prefix = "test_motion_plans.put_first.fetch_non_matching_out_of_tolerance"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, close_matching_plan_req, 0, 0); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, close_matching_plan_req, 0, 0); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch non-matching, only start in tolerance (but not goal) + // + // Non-matching key should not have cache hit + prefix = + "test_motion_plans.put_first.fetch_non_matching_only_start_in_tolerance"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, close_matching_plan_req, 999, 0); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, close_matching_plan_req, 999, 0); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch non-matching, only goal in tolerance (but not start) + // + // Non-matching key should not have cache hit + prefix = + "test_motion_plans.put_first.fetch_non_matching_only_goal_in_tolerance"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, close_matching_plan_req, 0, 999); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, close_matching_plan_req, 0, 999); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch non-matching, in tolerance + // + // Close key within tolerance limit should have cache hit + prefix = "test_motion_plans.put_first.fetch_non_matching_in_tolerance"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, close_matching_plan_req, 0.1, 0.1); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, close_matching_plan_req, 0.1, 0.1); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + // Fetch swapped + // + // Matches should be mostly invariant to constraint ordering + prefix = "test_motion_plans.put_first.fetch_swapped"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, swapped_close_matching_plan_req, 0.1, 0.1); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, swapped_close_matching_plan_req, 0.1, 0.1); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + // Fetch with smaller workspace + // + // Matching plans with more restrictive workspace requirements should not + // pull up plans cached for less restrictive workspace requirements + prefix = "test_motion_plans.put_first.fetch_smaller_workspace"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, smaller_workspace_plan_req, 999, 999); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, smaller_workspace_plan_req, 999, 999); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch with larger workspace + // + // Matching plans with less restrictive workspace requirements should pull up + // plans cached for more restrictive workspace requirements + prefix = "test_motion_plans.put_first.fetch_larger_workspace"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, larger_workspace_plan_req, 999, 999); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, larger_workspace_plan_req, 999, 999); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble( + "workspace_parameters.max_corner.x") + <= larger_workspace_plan_req.workspace_parameters.max_corner.x, + prefix, "Fetched plan has more restrictive workspace max_corner"); + + check_and_emit( + fetched_plan->lookupDouble( + "workspace_parameters.max_corner.x") + >= larger_workspace_plan_req.workspace_parameters.min_corner.x, + prefix, "Fetched plan has more restrictive workspace min_corner"); + + // Put worse, no delete_worse_plans + // + // Worse plans should not be inserted + prefix = "test_motion_plans.put_worse"; + double worse_execution_time = execution_time + 100; + + check_and_emit( + !cache->put_plan( + *move_group, g_robot_name, plan_req, plan, + worse_execution_time, planning_time, false), + prefix, "Put worse plan, no delete_worse_plans, not ok"); + + check_and_emit( + cache->count_plans(g_robot_name) == 1, prefix, "One plan in cache"); + + // Put better, no delete_worse_plans + // + // Better plans should be inserted + prefix = "test_motion_plans.put_better"; + double better_execution_time = execution_time - 100; + + check_and_emit( + cache->put_plan( + *move_group, g_robot_name, plan_req, plan, + better_execution_time, planning_time, false), + prefix, "Put better plan, no delete_worse_plans, ok"); + + check_and_emit( + cache->count_plans(g_robot_name) == 2, prefix, "Two plans in cache"); + + // Fetch sorted + // + // With multiple plans in cache, fetches should be sorted accordingly + prefix = "test_motion_plans.put_better.fetch_sorted"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, plan_req, 0, 0); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, plan_req, 0, 0); + + check_and_emit(fetched_plans.size() == 2, prefix, "Fetch all returns two"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == better_execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plans.at(0)->lookupDouble( + "execution_time_s") == better_execution_time + && fetched_plans.at(1)->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plans are sorted correctly"); + + // Put better, delete_worse_plans + // + // Better, different, plans should be inserted + prefix = "test_motion_plans.put_better_delete_worse_plans"; + double even_better_execution_time = better_execution_time - 100; + + check_and_emit( + cache->put_plan( + *move_group, g_robot_name, plan_req, different_plan, + even_better_execution_time, planning_time, true), + prefix, "Put better plan, delete_worse_plans, ok"); + + check_and_emit( + cache->count_plans(g_robot_name) == 1, prefix, "One plan in cache"); + + // Fetch better plan + prefix = "test_motion_plans.put_better_delete_worse_plans.fetch"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, plan_req, 0, 0); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, plan_req, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == different_plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble( + "execution_time_s") == even_better_execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + // Put different req, delete_worse_plans + // + // Unrelated plan requests should live alongside pre-existing plans + prefix = "test_motion_plans.put_different_req"; + + check_and_emit( + cache->put_plan( + *move_group, g_robot_name, different_plan_req, different_plan, + better_execution_time, planning_time, true), + prefix, "Put different plan req, delete_worse_plans, ok"); + + check_and_emit( + cache->count_plans(g_robot_name) == 2, prefix, "Two plans in cache"); + + // Fetch with different plan req + // + // With multiple plans in cache, fetches should be sorted accordingly + prefix = "test_motion_plans.put_different_req.fetch"; + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, different_plan_req, 0, 0); + + fetched_plan = cache->fetch_best_matching_plan( + *move_group, g_robot_name, different_plan_req, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == different_plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble( + "execution_time_s") == better_execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + // Fetch different robot + // + // Since we didn't populate anything, we should expect empty + prefix = "test_motion_plans.different_robot.empty"; + std::string different_robot_name = "different_robot"; + + check_and_emit( + cache->count_cartesian_plans(different_robot_name) == 0, + prefix, "No plans in cache"); + + // Put first for different robot, delete_worse_plans + // + // A different robot's cache should not interact with the original cache + prefix = "test_motion_plans.different_robot.put_first"; + check_and_emit( + cache->put_plan( + *move_group, different_robot_name, different_plan_req, + different_plan, better_execution_time, planning_time, true), + prefix, "Put different plan req, delete_worse_plans, ok"); + + check_and_emit( + cache->count_plans(different_robot_name) == 1, + prefix, "One plans in cache"); + + check_and_emit( + cache->count_plans(different_robot_name) == 1, + prefix, "One plans in cache"); + + check_and_emit( + cache->count_plans(g_robot_name) == 2, + prefix, "Two plans in original robot's cache"); + + fetched_plans = cache->fetch_all_matching_plans( + *move_group, g_robot_name, different_plan_req, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, + "Fetch all on original still returns one"); +} + +void test_cartesian_plans( + std::shared_ptr move_group, + std::shared_ptr cache) +{ + std::string prefix; + + /// First, test if construction even works... + + // Construct get cartesian plan request + prefix = "test_cartesian_plans.construct_get_cartesian_path_request"; + + int test_step = 1; + int test_jump = 2; + auto test_waypoints = get_dummy_waypoints(); + auto cartesian_plan_req_under_test = + cache->construct_get_cartesian_plan_request( + *move_group, test_waypoints, test_step, test_jump, false); + + check_and_emit( + cartesian_plan_req_under_test.waypoints == test_waypoints + && static_cast( + cartesian_plan_req_under_test.max_step) == test_step + && static_cast( + cartesian_plan_req_under_test.jump_threshold) == test_jump + && !cartesian_plan_req_under_test.avoid_collisions, + prefix, "Ok"); + + // Setup ===================================================================== + // All variants are copies. + + /// GetCartesianPath::Request + + // Plain start + auto waypoints = get_dummy_waypoints(); + auto cartesian_plan_req = cache + ->construct_get_cartesian_plan_request(*move_group, waypoints, 1, 1, false); + cartesian_plan_req.start_state.multi_dof_joint_state.joint_names.clear(); + cartesian_plan_req.start_state.multi_dof_joint_state.transforms.clear(); + cartesian_plan_req.start_state.multi_dof_joint_state.twist.clear(); + cartesian_plan_req.start_state.multi_dof_joint_state.wrench.clear(); + cartesian_plan_req.path_constraints.joint_constraints.clear(); + cartesian_plan_req.path_constraints.position_constraints.clear(); + cartesian_plan_req.path_constraints.orientation_constraints.clear(); + cartesian_plan_req.path_constraints.visibility_constraints.clear(); + + // Empty frame start + auto empty_frame_cartesian_plan_req = cartesian_plan_req; + empty_frame_cartesian_plan_req.header.frame_id = ""; + + // is_diff = true + auto is_diff_cartesian_plan_req = cartesian_plan_req; + is_diff_cartesian_plan_req.start_state.is_diff = true; + is_diff_cartesian_plan_req.start_state.joint_state.header.frame_id = ""; + is_diff_cartesian_plan_req.start_state.joint_state.name.clear(); + is_diff_cartesian_plan_req.start_state.joint_state.position.clear(); + is_diff_cartesian_plan_req.start_state.joint_state.velocity.clear(); + is_diff_cartesian_plan_req.start_state.joint_state.effort.clear(); + + // Something close enough (mod 0.1 away) + auto close_matching_cartesian_plan_req = cartesian_plan_req; + close_matching_cartesian_plan_req.start_state.joint_state.position.at(0) -= + 0.05; + close_matching_cartesian_plan_req.start_state.joint_state.position.at(1) += + 0.05; + close_matching_cartesian_plan_req.start_state.joint_state.position.at(2) -= + 0.05; + close_matching_cartesian_plan_req.waypoints.at(0).position.x -= 0.05; + close_matching_cartesian_plan_req.waypoints.at(1).position.x += 0.05; + close_matching_cartesian_plan_req.waypoints.at(2).position.x -= 0.05; + + // Different + auto different_cartesian_plan_req = cartesian_plan_req; + different_cartesian_plan_req.start_state.joint_state.position.at(0) -= 1.05; + different_cartesian_plan_req.start_state.joint_state.position.at(1) += 2.05; + different_cartesian_plan_req.start_state.joint_state.position.at(2) -= 3.05; + different_cartesian_plan_req.waypoints.at(0).position.x -= 1.05; + different_cartesian_plan_req.waypoints.at(1).position.x += 2.05; + different_cartesian_plan_req.waypoints.at(2).position.x -= 3.05; + + /// RobotTrajectory + + // Plan + auto plan = get_dummy_panda_plan(); + + // Plan with no frame_id in its trajectory header + auto empty_frame_plan = plan; + empty_frame_plan.joint_trajectory.header.frame_id = ""; + + auto different_plan = plan; + different_plan.joint_trajectory.points.at(0).positions.at(0) = 999; + different_plan.joint_trajectory.points.at(0).positions.at(1) = 999; + different_plan.joint_trajectory.points.at(0).positions.at(2) = 999; + + // Checks ==================================================================== + + // Initially empty + prefix = "test_cartesian_plans.empty"; + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 0, + prefix, "Plan cache initially empty"); + + check_and_emit( + cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, cartesian_plan_req, 0, 999, 999).empty(), + prefix, "Fetch all plans on empty cache returns empty"); + + check_and_emit( + cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, 0, 999, 999) == nullptr, + prefix, "Fetch best plan on empty cache returns nullptr"); + + // Put plan empty frame + // + // Plan must have frame in joint trajectory, expect put fail + prefix = "test_cartesian_plans.put_plan_empty_frame"; + double execution_time = 999; + double planning_time = 999; + double fraction = 0.5; + + check_and_emit( + !cache->put_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, empty_frame_plan, + execution_time, planning_time, fraction, false), + prefix, "Put empty frame plan, no delete_worse_plans, not ok"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 0, + prefix, "No plans in cache"); + + // Put plan req empty frame + // + // Plan request must have frame in workspace, expect put fail + prefix = "test_cartesian_plans.put_plan_req_empty_frame"; + execution_time = 999; + planning_time = 999; + + check_and_emit( + !cache->put_cartesian_plan( + *move_group, g_robot_name, empty_frame_cartesian_plan_req, plan, + execution_time, planning_time, fraction, false), + prefix, "Put empty frame req plan, no delete_worse_plans, not ok"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 0, + prefix, "No plans in cache"); + + // Put first, no delete_worse_plans + prefix = "test_cartesian_plans.put_first"; + execution_time = 999; + planning_time = 999; + + check_and_emit( + cache->put_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, plan, + execution_time, planning_time, fraction, false), + prefix, "Put first valid plan, no delete_worse_plans, ok"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 1, + prefix, "One plan in cache"); + + // Fetch matching, no tolerance + // + // Exact key match should have cache hit + prefix = "test_cartesian_plans.put_first.fetch_matching_no_tolerance"; + + auto fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, cartesian_plan_req, fraction, 0, 0); + + auto fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, fraction, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble("fraction") == fraction, + prefix, "Fetched plan has correct fraction"); + + // Fetch with is_diff + // + // is_diff key should be equivalent to exact match if robot state did not + // change, hence should have cache hit + prefix = "test_cartesian_plans.put_first.fetch_is_diff_no_tolerance"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, is_diff_cartesian_plan_req, fraction, 0, 0); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, is_diff_cartesian_plan_req, fraction, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble("fraction") == fraction, + prefix, "Fetched plan has correct fraction"); + + // Fetch non-matching, out of tolerance + // + // Non-matching key should not have cache hit + prefix = "test_cartesian_plans.put_first.fetch_non_matching_out_of_tolerance"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 0, 0); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 0, 0); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch non-matching, only start in tolerance (but not goal) + // + // Non-matching key should not have cache hit + prefix = + "test_motion_plans.put_first.fetch_non_matching_only_start_in_tolerance"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 999, 0); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 999, 0); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch non-matching, only goal in tolerance (but not start) + // + // Non-matching key should not have cache hit + prefix = + "test_motion_plans.put_first.fetch_non_matching_only_goal_in_tolerance"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 0, 999); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 0, 999); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch non-matching, in tolerance + // + // Close key within tolerance limit should have cache hit + prefix = "test_cartesian_plans.put_first.fetch_non_matching_in_tolerance"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 0.1, 0.1); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, close_matching_cartesian_plan_req, + fraction, 0.1, 0.1); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble("fraction") == fraction, + prefix, "Fetched plan has correct fraction"); + + // Fetch with higher fraction + // + // Matching plans with more restrictive fraction requirements should not + // pull up plans cached for less restrictive fraction requirements + prefix = "test_cartesian_plans.put_first.fetch_higher_fraction"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, cartesian_plan_req, 1, 999, 999); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, 1, 999, 999); + + check_and_emit(fetched_plans.size() == 0, prefix, "Fetch all returns empty"); + check_and_emit( + fetched_plan == nullptr, prefix, "Fetch best plan is nullptr"); + + // Fetch with lower fraction + // + // Matching plans with less restrictive fraction requirements should pull up + // plans cached for more restrictive fraction requirements + prefix = "test_cartesian_plans.put_first.fetch_lower_fraction"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, cartesian_plan_req, 0, 999, 999); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, 0, 999, 999); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble("fraction") == fraction, + prefix, "Fetched plan has correct fraction"); + + // Put worse, no delete_worse_plans + // + // Worse plans should not be inserted + prefix = "test_cartesian_plans.put_worse"; + double worse_execution_time = execution_time + 100; + + check_and_emit( + !cache->put_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, plan, + worse_execution_time, planning_time, fraction, false), + prefix, "Put worse plan, no delete_worse_plans, not ok"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 1, + prefix, "One plan in cache"); + + // Put better, no delete_worse_plans + // + // Better plans should be inserted + prefix = "test_cartesian_plans.put_better"; + double better_execution_time = execution_time - 100; + + check_and_emit( + cache->put_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, plan, + better_execution_time, planning_time, fraction, false), + prefix, "Put better plan, no delete_worse_plans, ok"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 2, + prefix, "Two plans in cache"); + + // Fetch sorted + // + // With multiple plans in cache, fetches should be sorted accordingly + prefix = "test_cartesian_plans.put_better.fetch_sorted"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, cartesian_plan_req, fraction, 0, 0); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, fraction, 0, 0); + + check_and_emit(fetched_plans.size() == 2, prefix, "Fetch all returns two"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble("execution_time_s") == better_execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble("fraction") == fraction, + prefix, "Fetched plan has correct fraction"); + + check_and_emit( + fetched_plans.at(0)->lookupDouble( + "execution_time_s") == better_execution_time + && fetched_plans.at(1)->lookupDouble("execution_time_s") == execution_time, + prefix, "Fetched plans are sorted correctly"); + + // Put better, delete_worse_plans + // + // Better, different, plans should be inserted + prefix = "test_cartesian_plans.put_better_delete_worse_plans"; + double even_better_execution_time = better_execution_time - 100; + + check_and_emit( + cache->put_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, different_plan, + even_better_execution_time, planning_time, fraction, true), + prefix, "Put better plan, delete_worse_plans, ok"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 1, + prefix, "One plan in cache"); + + // Fetch better plan + prefix = "test_cartesian_plans.put_better_delete_worse_plans.fetch"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, cartesian_plan_req, fraction, 0, 0); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, cartesian_plan_req, fraction, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == different_plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble( + "execution_time_s") == even_better_execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble("fraction") == fraction, + prefix, "Fetched plan has correct fraction"); + + // Put different req, delete_worse_plans + // + // Unrelated plan requests should live alongside pre-existing plans + prefix = "test_cartesian_plans.put_different_req"; + + check_and_emit( + cache->put_cartesian_plan( + *move_group, g_robot_name, different_cartesian_plan_req, different_plan, + better_execution_time, planning_time, fraction, true), + prefix, "Put different plan req, delete_worse_plans, ok"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 2, + prefix, "Two plans in cache"); + + // Fetch with different plan req + // + // With multiple plans in cache, fetches should be sorted accordingly + prefix = "test_cartesian_plans.put_different_req.fetch"; + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, different_cartesian_plan_req, fraction, 0, 0); + + fetched_plan = cache->fetch_best_matching_cartesian_plan( + *move_group, g_robot_name, different_cartesian_plan_req, fraction, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, "Fetch all returns one"); + check_and_emit( + fetched_plan != nullptr, prefix, "Fetch best plan is not nullptr"); + + check_and_emit( + *fetched_plans.at(0) == *fetched_plan, + prefix, "Fetched plan on both fetches match"); + + check_and_emit( + *fetched_plan == different_plan, prefix, "Fetched plan matches original"); + + check_and_emit( + fetched_plan->lookupDouble( + "execution_time_s") == better_execution_time, + prefix, "Fetched plan has correct execution time"); + + check_and_emit( + fetched_plan->lookupDouble("planning_time_s") == planning_time, + prefix, "Fetched plan has correct planning time"); + + check_and_emit( + fetched_plan->lookupDouble("fraction") == fraction, + prefix, "Fetched plan has correct fraction"); + + // Fetch different robot + // + // Since we didn't populate anything, we should expect empty + prefix = "test_cartesian_plans.different_robot.empty"; + std::string different_robot_name = "different_robot"; + + check_and_emit( + cache->count_cartesian_plans(different_robot_name) == 0, + prefix, "No plans in cache"); + + // Put first for different robot, delete_worse_plans + // + // A different robot's cache should not interact with the original cache + prefix = "test_cartesian_plans.different_robot.put_first"; + check_and_emit( + cache->put_cartesian_plan( + *move_group, different_robot_name, different_cartesian_plan_req, + different_plan, better_execution_time, planning_time, fraction, true), + prefix, "Put different plan req, delete_worse_plans, ok"); + + check_and_emit( + cache->count_cartesian_plans(different_robot_name) == 1, + prefix, "One plans in cache"); + + check_and_emit( + cache->count_cartesian_plans(different_robot_name) == 1, + prefix, "One plans in cache"); + + check_and_emit( + cache->count_cartesian_plans(g_robot_name) == 2, + prefix, "Two plans in original robot's cache"); + + fetched_plans = cache->fetch_all_matching_cartesian_plans( + *move_group, g_robot_name, different_cartesian_plan_req, fraction, 0, 0); + + check_and_emit(fetched_plans.size() == 1, prefix, + "Fetch all on original still returns one"); +} + +int main(int argc, char** argv) +{ + // Setup + rclcpp::init(argc, argv); + rclcpp::NodeOptions node_options; + node_options.automatically_declare_parameters_from_overrides(true); + + auto test_node = rclcpp::Node::make_shared("test_node", node_options); + std::thread spin_thread( + [&]() + { + while (rclcpp::ok()) + { + rclcpp::spin_some(test_node); + } + } + ); + + // This is necessary + test_node->declare_parameter( + "warehouse_plugin", "warehouse_ros_sqlite::DatabaseConnection"); + + // Test proper + { + auto cache = std::make_shared(test_node); + check_and_emit(cache->init(":memory:", 0, 1e-4), "init", "Cache init"); + + auto move_group = + std::make_shared(test_node, "panda_arm"); + + auto curr_state = move_group->getCurrentState(); + move_group->setStartState(*curr_state); + + test_motion_plans(move_group, cache); + test_cartesian_plans(move_group, cache); + } + + rclcpp::shutdown(); + spin_thread.join(); + + return 0; +} + +// CARTESIAN PLANS === + +// Check construct plan request +// Remember to check fraction too! \ No newline at end of file diff --git a/nexus_motion_planner/test/test_motion_plan_cache.py b/nexus_motion_planner/test/test_motion_plan_cache.py new file mode 100755 index 0000000..e73cbb1 --- /dev/null +++ b/nexus_motion_planner/test/test_motion_plan_cache.py @@ -0,0 +1,148 @@ +# Copyright 2023 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. + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch_pytest.tools import process as process_tools +from launch_ros.actions import Node + +from moveit_configs_utils import MoveItConfigsBuilder + +import launch_pytest + +import pytest +import os + +# This would have been a gtest, but we need a move_group instance, which +# requires some parameters loaded and a separate node started. + + +@pytest.fixture +def moveit_config(): + return ( + MoveItConfigsBuilder("moveit_resources_panda") + .robot_description(file_path="config/panda.urdf.xacro") + .planning_pipelines("ompl", ["ompl"]) # Sadly necessary + .trajectory_execution(file_path="config/gripper_moveit_controllers.yaml") + .to_moveit_configs() + ) + + +# We need this so the move_group has something to interact with +@pytest.fixture +def robot_fixture(moveit_config): + run_move_group_node = Node( + package="moveit_ros_move_group", + executable="move_group", + output="log", + parameters=[moveit_config.to_dict()], + ) + + static_tf = Node( + package="tf2_ros", + executable="static_transform_publisher", + output="log", + arguments=["0.0", "0.0", "0.0", "0.0", + "0.0", "0.0", "world", "panda_link0"], + ) + + robot_state_publisher = Node( + package="robot_state_publisher", + executable="robot_state_publisher", + name="robot_state_publisher", + output="log", + parameters=[moveit_config.robot_description], + ) + + # ros2_control using FakeSystem as hardware + ros2_controllers_path = os.path.join( + get_package_share_directory("moveit_resources_panda_moveit_config"), + "config", + "ros2_controllers.yaml", + ) + ros2_control_node = Node( + package="controller_manager", + executable="ros2_control_node", + parameters=[moveit_config.robot_description, ros2_controllers_path], + output="log", + ) + + load_controllers = [] + for controller in [ + "panda_arm_controller", + "panda_hand_controller", + "joint_state_broadcaster", + ]: + load_controllers += [ + ExecuteProcess( + cmd=["ros2 run controller_manager spawner {}".format( + controller)], + shell=True, + output="log", + ) + ] + + return [ + run_move_group_node, + static_tf, + robot_state_publisher, + ros2_control_node, + *load_controllers + ] + + +@pytest.fixture +def motion_cache_test_runner_node(moveit_config): + return Node( + package="nexus_motion_planner", + executable="test_motion_plan_cache", + name="test_motion_plan_cache_node", + output="screen", + cached_output=True, + parameters=[moveit_config.to_dict()] + ) + + +@launch_pytest.fixture +def launch_description(motion_cache_test_runner_node, robot_fixture): + return LaunchDescription( + robot_fixture + + [ + motion_cache_test_runner_node, + launch_pytest.actions.ReadyToTest() + ] + ) + + +def validate_stream(expected): + def wrapped(output): + assert expected in output.splitlines( + ), f"Did not get expected: {expected} in output:\n\n{output}" + return wrapped + + +@pytest.mark.launch(fixture=launch_description) +def test_all_tests_pass(motion_cache_test_runner_node, launch_context): + # Check no occurrences of [FAIL] in output + assert not process_tools.wait_for_output_sync( + launch_context, + motion_cache_test_runner_node, + lambda x: "[FAIL]" in x, + timeout=10 + ) + + # Wait for process to end and check for graceful exit + yield + assert motion_cache_test_runner_node.return_code == 0 diff --git a/nexus_msgs/nexus_motion_planner_msgs/srv/GetMotionPlan.srv b/nexus_msgs/nexus_motion_planner_msgs/srv/GetMotionPlan.srv index 87cc18f..a883d18 100644 --- a/nexus_msgs/nexus_motion_planner_msgs/srv/GetMotionPlan.srv +++ b/nexus_msgs/nexus_motion_planner_msgs/srv/GetMotionPlan.srv @@ -52,6 +52,11 @@ string payload float64 max_velocity_scaling_factor float64 max_acceleration_scaling_factor +# Set to true in order to force the server to use the motion cache as if the +# cache mode were set to ExecuteReadOnly, regardless of the original setting +# for this request. +bool force_cache_mode_execute_read_only + --- # Motion planning result diff --git a/nexus_tree_nodes.xml b/nexus_tree_nodes.xml index e9e7efa..9d36669 100644 --- a/nexus_tree_nodes.xml +++ b/nexus_tree_nodes.xml @@ -52,6 +52,7 @@ An optional fraction [0,1] to scale the acceleraton and speed of the generated trajectory True if a cartesian plan is required If provided the joint_constraints will be used as the start state of the robot. By default the current state is set as start + True to force cache mode to ExecuteReadOnly for this request. The generated motion plan