Skip to content

Commit

Permalink
remove unused fixed frame parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Feb 9, 2024
1 parent b2bfd87 commit 3d5146c
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,6 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock
// Optionally subscribe to a detected dock pose topic
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
std::string fixed_frame_;
geometry_msgs::msg::PoseStamped dock_pose_, detected_dock_pose_;

// Subscribe to battery message, used to determine if charging
Expand Down
3 changes: 0 additions & 3 deletions opennav_docking/src/simple_charging_dock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,6 @@ void SimpleChargingDock::configure(
node_, name + ".staging_x_offset", rclcpp::ParameterValue(-0.5));
nav2_util::declare_parameter_if_not_declared(
node_, name + ".staging_yaw_offset", rclcpp::ParameterValue(0.0));
nav2_util::declare_parameter_if_not_declared(
node_, "fixed_frame", rclcpp::ParameterValue("odom"));

node_->get_parameter(name + ".use_external_detection_pose", use_external_detection_pose_);
node_->get_parameter(name + ".external_detection_timeout", external_detection_timeout_);
Expand All @@ -74,7 +72,6 @@ void SimpleChargingDock::configure(
node_->get_parameter(name + ".docking_threshold", docking_threshold_);
node_->get_parameter(name + ".staging_x_offset", staging_x_offset_);
node_->get_parameter(name + ".staging_yaw_offset", staging_yaw_offset_);
node_->get_parameter("fixed_frame", fixed_frame_);

battery_sub_ = node_->create_subscription<sensor_msgs::msg::BatteryState>(
"battery_state", 1,
Expand Down

0 comments on commit 3d5146c

Please sign in to comment.