19#ifndef EASYNAV_CONTROLLER__VFFCONTROLLER_HPP_
20#define EASYNAV_CONTROLLER__VFFCONTROLLER_HPP_
22#include "pcl/point_cloud.h"
24#include "easynav_core/ControllerMethodBase.hpp"
26#include "geometry_msgs/msg/twist_stamped.hpp"
27#include "visualization_msgs/msg/marker.hpp"
28#include "visualization_msgs/msg/marker_array.hpp"
92 virtual void update_rt(NavState & nav_state)
override;
98 geometry_msgs::msg::TwistStamped cmd_vel_;
103 geometry_msgs::msg::Point goal_;
111 double normalize_angle(
double angle);
121 const pcl::PointCloud<pcl::PointXYZ> & pointcloud_, std::string frame_id);
128 rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr marker_array_pub_;
140 visualization_msgs::msg::Marker make_marker(
141 const std::vector<double> & vector,
142 VFFColor vff_color, std::string frame_id);
153 visualization_msgs::msg::MarkerArray get_debug_vff(
155 std::string frame_id);
163 float distance_obstacle_detection_;
170 float obstacle_detection_x_min_;
171 float obstacle_detection_x_max_;
172 float obstacle_detection_y_min_;
173 float obstacle_detection_y_max_;
174 float obstacle_detection_z_min_;
175 float obstacle_detection_z_max_;
189 double max_angular_speed_;
~VffController()=default
Default destructor.
virtual void update_rt(NavState &nav_state) override
Updates the localization estimate based on the current navigation state.
Definition VffController.cpp:204
VffController()=default
Default constructor.
virtual void on_initialize() override
Initializes the control method plugin.
Definition VffController.cpp:32
Provides a mapping for often used cost values.
Definition cost_values.hpp:41
VFFColor
An enumeration to represent the color of the VFF vectors.
Definition VffController.hpp:52
@ BLUE
Definition VffController.hpp:52
@ GREEN
Definition VffController.hpp:52
@ RED
Definition VffController.hpp:52
A structure to hold the VFF vectors.
Definition VffController.hpp:40
std::vector< double > result
Definition VffController.hpp:43
std::vector< double > attractive
Definition VffController.hpp:41
std::vector< double > repulsive
Definition VffController.hpp:42