Skip to content

Commit

Permalink
Default to warehouse_ros plugin if warehouse plugin isn't set
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 6ad592e commit 5563f3c
Showing 1 changed file with 2 additions and 6 deletions.
8 changes: 2 additions & 6 deletions nexus_motion_planner/src/motion_plan_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,17 +41,13 @@ void queryAppendRangeInclusiveWithTolerance(
MotionPlanCache::MotionPlanCache(const rclcpp::Node::SharedPtr& node)
: node_(node)
{
if (!node_->has_parameter("warehouse_plugin"))
{
node_->declare_parameter<std::string>(
"warehouse_plugin", "warehouse_ros_sqlite::DatabaseConnection");
}

tf_buffer_ =
std::make_unique<tf2_ros::Buffer>(node_->get_clock());
tf_listener_ =
std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);

// If the `warehouse_plugin` parameter isn't set, defaults to warehouse_ros'
// default.
warehouse_ros::DatabaseLoader loader(node_);
db_ = loader.loadDatabase();
}
Expand Down

0 comments on commit 5563f3c

Please sign in to comment.