Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

remove unused odometry smoother in bt navigator #2829

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ class BtNavigator : public nav2_util::LifecycleNode
nav2_bt_navigator::NavigatorMuxer plugin_muxer_;

// Odometry smoother object
std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;

// Metrics for feedback
std::string robot_frame_;
Expand Down
13 changes: 10 additions & 3 deletions nav2_bt_navigator/include/nav2_bt_navigator/navigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,13 +135,15 @@ class Navigator
* @param feedback_utils Some utilities useful for navigators to have
* @param plugin_muxer The muxing object to ensure only one navigator
* can be active at a time
* @param odom_smoother Object to get current smoothed robot's speed
* @return bool If successful
*/
bool on_configure(
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
const std::vector<std::string> & plugin_lib_names,
const FeedbackUtils & feedback_utils,
nav2_bt_navigator::NavigatorMuxer * plugin_muxer)
nav2_bt_navigator::NavigatorMuxer * plugin_muxer,
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
{
auto node = parent_node.lock();
logger_ = node->get_logger();
Expand Down Expand Up @@ -173,7 +175,7 @@ class Navigator
blackboard->set<bool>("initial_pose_received", false); // NOLINT
blackboard->set<int>("number_recoveries", 0); // NOLINT

return configure(parent_node) && ok;
return configure(parent_node, odom_smoother) && ok;
}

/**
Expand Down Expand Up @@ -293,7 +295,12 @@ class Navigator
/**
* @param Method to configure resources.
*/
virtual bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr /*node*/) {return true;}
virtual bool configure(
rclcpp_lifecycle::LifecycleNode::WeakPtr /*node*/
std::shared_ptr<nav2_util::OdomSmoother> /*odom_smoother*/)
{
return true;
}

/**
* @brief Method to cleanup resources.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +51,11 @@ class NavigateThroughPosesNavigator
/**
* @brief A configure state transition to configure navigator's state
* @param node Weakptr to the lifecycle node
* @param odom_smoother Object to get current smoothed robot's speed
*/
bool configure(
rclcpp_lifecycle::LifecycleNode::WeakPtr node) override;
rclcpp_lifecycle::LifecycleNode::WeakPtr node,
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) override;

/**
* @brief Get action name for this navigator
Expand Down Expand Up @@ -106,7 +108,7 @@ class NavigateThroughPosesNavigator
std::string path_blackboard_id_;

// Odometry smoother object
std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
};

} // namespace nav2_bt_navigator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,11 @@ class NavigateToPoseNavigator
/**
* @brief A configure state transition to configure navigator's state
* @param node Weakptr to the lifecycle node
* @param odom_smoother Object to get current smoothed robot's speed
*/
bool configure(
rclcpp_lifecycle::LifecycleNode::WeakPtr node) override;
rclcpp_lifecycle::LifecycleNode::WeakPtr node,
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother) override;

/**
* @brief A cleanup state transition to remove memory allocated
Expand Down Expand Up @@ -122,7 +124,7 @@ class NavigateToPoseNavigator
std::string path_blackboard_id_;

// Odometry smoother object
std::unique_ptr<nav2_util::OdomSmoother> odom_smoother_;
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
};

} // namespace nav2_bt_navigator
Expand Down
10 changes: 5 additions & 5 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,21 +111,21 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
feedback_utils.robot_frame = robot_frame_;
feedback_utils.transform_tolerance = transform_tolerance_;

// Odometry smoother object for getting current speed
odom_smoother_ = std::make_shared<nav2_util::OdomSmoother>(shared_from_this(), 0.3, odom_topic_)

if (!pose_navigator_->on_configure(
shared_from_this(), plugin_lib_names, feedback_utils, &plugin_muxer_))
shared_from_this(), plugin_lib_names, feedback_utils, &plugin_muxer_, odom_smoother_))
{
return nav2_util::CallbackReturn::FAILURE;
}

if (!poses_navigator_->on_configure(
shared_from_this(), plugin_lib_names, feedback_utils, &plugin_muxer_))
shared_from_this(), plugin_lib_names, feedback_utils, &plugin_muxer_, odom_smoother_))
{
return nav2_util::CallbackReturn::FAILURE;
}

// Odometry smoother object for getting current speed
odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(shared_from_this(), 0.3, odom_topic_);

return nav2_util::CallbackReturn::SUCCESS;
}

Expand Down
5 changes: 3 additions & 2 deletions nav2_bt_navigator/src/navigators/navigate_through_poses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ namespace nav2_bt_navigator

bool
NavigateThroughPosesNavigator::configure(
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node)
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
{
start_time_ = rclcpp::Time(0);
auto node = parent_node.lock();
Expand All @@ -36,7 +37,7 @@ NavigateThroughPosesNavigator::configure(
path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();

// Odometry smoother object for getting current speed
odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(node, 0.3);
odom_smoother_ = odom_smoother;

return true;
}
Expand Down
5 changes: 3 additions & 2 deletions nav2_bt_navigator/src/navigators/navigate_to_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ namespace nav2_bt_navigator

bool
NavigateToPoseNavigator::configure(
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node)
rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
{
start_time_ = rclcpp::Time(0);
auto node = parent_node.lock();
Expand All @@ -36,7 +37,7 @@ NavigateToPoseNavigator::configure(
path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();

// Odometry smoother object for getting current speed
odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(node, 0.3);
odom_smoother_ = odom_smoother;

self_client_ = rclcpp_action::create_client<ActionT>(node, getName());

Expand Down