Skip to content

Commit

Permalink
Update only use cached plans parameter name
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Sep 27, 2023
1 parent 6475ab9 commit 6a7a3d9
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 12 deletions.
23 changes: 12 additions & 11 deletions nexus_motion_planner/src/motion_planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -199,12 +199,12 @@ MotionPlannerServer::MotionPlannerServer(const rclcpp::NodeOptions& options)
_use_motion_plan_cache ? "True" : "False"
);

_only_use_cached_plans = this->declare_parameter(
"only_use_cached_plans", false);
_use_cached_plans_instead_of_planning = this->declare_parameter(
"use_cached_plans_instead_of_planning", false);
RCLCPP_INFO(
this->get_logger(),
"Setting parameter only_use_cached_plans to [%s]",
_only_use_cached_plans ? "True" : "False"
"Setting parameter use_cached_plans_instead_of_planning to [%s]",
_use_cached_plans_instead_of_planning ? "True" : "False"
);

_overwrite_worse_plans = this->declare_parameter(
Expand Down Expand Up @@ -235,7 +235,7 @@ MotionPlannerServer::MotionPlannerServer(const rclcpp::NodeOptions& options)
);

_cache_exact_match_tolerance = this->declare_parameter(
"cache_exact_match_tolerance", 0.00001);
"cache_exact_match_tolerance", 0.0005); // ~0.028 degrees per joint
RCLCPP_INFO(
this->get_logger(),
"Setting parameter cache_exact_match_tolerance to [%.2e]",
Expand Down Expand Up @@ -310,11 +310,12 @@ auto MotionPlannerServer::on_configure(const LifecycleState& /*state*/)
-> CallbackReturn
{
RCLCPP_INFO(this->get_logger(), "Configuring...");
if (!_use_motion_plan_cache && _only_use_cached_plans)
if (!_use_motion_plan_cache && _use_cached_plans_instead_of_planning)
{
RCLCPP_ERROR(
this->get_logger(),
"use_motion_plan_cache must be true if only_use_cached_plans is true."
"use_motion_plan_cache must be true if "
"use_cached_plans_instead_of_planning is true."
);
return CallbackReturn::ERROR;
}
Expand Down Expand Up @@ -642,7 +643,7 @@ void MotionPlannerServer::plan_with_move_group(
bool plan_is_from_cache = false;
interface->constructMotionPlanRequest(plan_req_msg);

if (!_only_use_cached_plans)
if (!_use_cached_plans_instead_of_planning)
{
res->result.error_code = interface->plan(plan);
RCLCPP_INFO(
Expand All @@ -667,16 +668,16 @@ void MotionPlannerServer::plan_with_move_group(
moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
RCLCPP_INFO(
this->get_logger(),
"Cache fetch took %es, planning time was: %es",
"Cache fetch took %es, planning time of fetched plan was: %es",
(fetch_end - fetch_start).seconds(),
fetched_plan->lookupDouble("planning_time_s"));
}
else
{
RCLCPP_ERROR(
this->get_logger(),
"only_use_cached_plans was true, and could not find cached plan for "
"plan request: \n\n%s",
"use_cached_plans_instead_of_planning was true, and could not find "
"cached plan for plan request: \n\n%s",
moveit_msgs::msg::to_yaml(plan_req_msg).c_str());
res->result.error_code.val =
moveit_msgs::msg::MoveItErrorCodes::FAILURE;
Expand Down
2 changes: 1 addition & 1 deletion nexus_motion_planner/src/motion_planner_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ class MotionPlannerServer : public rclcpp_lifecycle::LifecycleNode
std::shared_ptr<nexus::motion_planner::MotionPlanCache> _motion_plan_cache;

bool _use_motion_plan_cache;
bool _only_use_cached_plans;
bool _use_cached_plans_instead_of_planning;
bool _overwrite_worse_plans;
std::string _cache_db_plugin;
std::string _cache_db_host;
Expand Down

0 comments on commit 6a7a3d9

Please sign in to comment.