Program Listing for File collision_monitor_node.hpp
↰ Return to documentation for file (include/nav2_collision_monitor/collision_monitor_node.hpp
)
// Copyright (c) 2022 Samsung R&D Institute Russia
//
// 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 NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
#define NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
#include <string>
#include <vector>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "visualization_msgs/msg/marker_array.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "tf2/time.h"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
#include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/twist_publisher.hpp"
#include "nav2_util/twist_subscriber.hpp"
#include "nav2_msgs/msg/collision_monitor_state.hpp"
#include "nav2_collision_monitor/types.hpp"
#include "nav2_collision_monitor/polygon.hpp"
#include "nav2_collision_monitor/circle.hpp"
#include "nav2_collision_monitor/velocity_polygon.hpp"
#include "nav2_collision_monitor/source.hpp"
#include "nav2_collision_monitor/scan.hpp"
#include "nav2_collision_monitor/pointcloud.hpp"
#include "nav2_collision_monitor/range.hpp"
#include "nav2_collision_monitor/polygon_source.hpp"
namespace nav2_collision_monitor
{
class CollisionMonitor : public nav2_util::LifecycleNode
{
public:
explicit CollisionMonitor(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
~CollisionMonitor();
protected:
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
protected:
void cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg);
void cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg);
void publishVelocity(const Action & robot_action, const std_msgs::msg::Header & header);
bool getParameters(
std::string & cmd_vel_in_topic,
std::string & cmd_vel_out_topic,
std::string & state_topic);
bool configurePolygons(
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance);
bool configureSources(
const std::string & base_frame_id,
const std::string & odom_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
void process(const Velocity & cmd_vel_in, const std_msgs::msg::Header & header);
bool processStopSlowdownLimit(
const std::shared_ptr<Polygon> polygon,
const std::vector<Point> & collision_points,
const Velocity & velocity,
Action & robot_action) const;
bool processApproach(
const std::shared_ptr<Polygon> polygon,
const std::vector<Point> & collision_points,
const Velocity & velocity,
Action & robot_action) const;
void notifyActionState(
const Action & robot_action, const std::shared_ptr<Polygon> action_polygon) const;
void publishPolygons() const;
// ----- Variables -----
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
std::vector<std::shared_ptr<Polygon>> polygons_;
std::vector<std::shared_ptr<Source>> sources_;
// Input/output speed controls
std::unique_ptr<nav2_util::TwistSubscriber> cmd_vel_in_sub_;
std::unique_ptr<nav2_util::TwistPublisher> cmd_vel_out_pub_;
rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CollisionMonitorState>::SharedPtr
state_pub_;
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
collision_points_marker_pub_;
bool process_active_;
Action robot_action_prev_;
rclcpp::Time stop_stamp_;
rclcpp::Duration stop_pub_timeout_;
}; // class CollisionMonitor
} // namespace nav2_collision_monitor
#endif // NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_