Skip to content

Commit

Permalink
Rename overwrite to delete_worse_plans
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Nov 20, 2023
1 parent 06cdcf9 commit f5713a1
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 8 deletions.
10 changes: 4 additions & 6 deletions nexus_motion_planner/src/motion_plan_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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())
Expand Down Expand Up @@ -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)
{
Expand Down Expand Up @@ -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())
Expand Down Expand Up @@ -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)
{
Expand Down
5 changes: 3 additions & 2 deletions nexus_motion_planner/src/motion_plan_cache.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,14 +128,15 @@ 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 plan seen so far.
bool put_plan(
const moveit::planning_interface::MoveGroupInterface& move_group,
const std::string& move_group_namespace,
const moveit_msgs::msg::MotionPlanRequest& plan_request,
const moveit_msgs::msg::RobotTrajectory& plan,
double execution_time_s,
double planning_time_s,
bool overwrite = true);
bool delete_worse_plans = true);

// QUERY CONSTRUCTION
bool extract_and_append_plan_start_to_query(
Expand Down Expand Up @@ -217,7 +218,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(
Expand Down

0 comments on commit f5713a1

Please sign in to comment.