Program Listing for File navigator.hpp
↰ Return to documentation for file (include/opennav_docking/navigator.hpp
)
// Copyright (c) 2024 Open Navigation LLC
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef OPENNAV_DOCKING__NAVIGATOR_HPP_
#define OPENNAV_DOCKING__NAVIGATOR_HPP_
#include <vector>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "pluginlib/class_loader.hpp"
#include "pluginlib/class_list_macros.hpp"
#include "nav2_msgs/action/navigate_to_pose.hpp"
#include "nav2_util/node_utils.hpp"
#include "opennav_docking/utils.hpp"
#include "opennav_docking/types.hpp"
namespace opennav_docking
{
class Navigator
{
public:
using Nav2Pose = nav2_msgs::action::NavigateToPose;
using ActionClient = rclcpp_action::Client<Nav2Pose>;
explicit Navigator(const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent);
~Navigator() = default;
void activate();
void deactivate();
void goToPose(
const geometry_msgs::msg::PoseStamped & pose,
const rclcpp::Duration & max_staging_duration,
bool recursed = false);
protected:
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
rclcpp::CallbackGroup::SharedPtr callback_group_;
rclcpp::executors::SingleThreadedExecutor executor_;
ActionClient::SharedPtr nav_to_pose_client_;
std::string navigator_bt_xml_;
};
} // namespace opennav_docking
#endif // OPENNAV_DOCKING__NAVIGATOR_HPP_