Program Listing for File polygon.hpp

Return to documentation for file (include/nav2_collision_monitor/polygon.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__POLYGON_HPP_
#define NAV2_COLLISION_MONITOR__POLYGON_HPP_

#include <memory>
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/polygon_stamped.hpp"

#include "tf2/time.h"
#include "tf2_ros/buffer.h"

#include "nav2_util/lifecycle_node.hpp"
#include "nav2_costmap_2d/footprint_subscriber.hpp"

#include "nav2_collision_monitor/types.hpp"

namespace nav2_collision_monitor
{

class Polygon
{
public:
  Polygon(
    const nav2_util::LifecycleNode::WeakPtr & node,
    const std::string & polygon_name,
    const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
    const std::string & base_frame_id,
    const tf2::Duration & transform_tolerance);
  virtual ~Polygon();

  bool configure();
  void activate();
  void deactivate();

  std::string getName() const;
  ActionType getActionType() const;
  bool getEnabled() const;
  int getMinPoints() const;
  double getSlowdownRatio() const;
  double getLinearLimit() const;
  double getAngularLimit() const;
  double getTimeBeforeCollision() const;

  virtual void getPolygon(std::vector<Point> & poly) const;

  virtual bool isShapeSet();

  void updatePolygon();

  virtual int getPointsInside(const std::vector<Point> & points) const;

  double getCollisionTime(
    const std::vector<Point> & collision_points,
    const Velocity & velocity) const;

  void publish();

protected:
  bool getCommonParameters(std::string & polygon_pub_topic);

  virtual bool getParameters(
    std::string & polygon_sub_topic,
    std::string & polygon_pub_topic,
    std::string & footprint_topic);

  void updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);

  void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);

  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
    std::vector<rclcpp::Parameter> parameters);

  bool isPointInside(const Point & point) const;

  // ----- Variables -----

  nav2_util::LifecycleNode::WeakPtr node_;
  rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")};
  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;

  // Basic parameters
  std::string polygon_name_;
  ActionType action_type_;
  int min_points_;
  double slowdown_ratio_;
  double linear_limit_;
  double angular_limit_;
  double time_before_collision_;
  double simulation_time_step_;
  bool enabled_;
  bool polygon_subscribe_transient_local_;
  rclcpp::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_sub_;
  std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;

  // Global variables
  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
  std::string base_frame_id_;
  tf2::Duration transform_tolerance_;

  // Visualization
  bool visualize_;
  geometry_msgs::msg::PolygonStamped polygon_;
  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_pub_;

  std::vector<Point> poly_;
};  // class Polygon

}  // namespace nav2_collision_monitor

#endif  // NAV2_COLLISION_MONITOR__POLYGON_HPP_