Added collision avoidance to MoveGlobal routine

This commit is contained in:
2025-05-05 01:34:53 +02:00
parent a160af8de3
commit ccfd1189c2
30 changed files with 792 additions and 33 deletions

View File

@ -17,6 +17,8 @@
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/buffer.h"
#include "mg_obstacles/mg_obstacles.hpp"
#include "path_buffer.hpp"
namespace mg {
@ -47,12 +49,14 @@ namespace mg {
MgNavigationServer(rclcpp::NodeOptions& opts);
std::shared_ptr<PathBuffer> path_buffer() { return path_buffer_; }
std::shared_ptr<PathBuffer> path_buffer() { return path_buffer_; }
std::shared_ptr<ObstacleManager>& obstacle_manager() { return obstacle_manager_; }
private:
bool is_processing = false;
std::shared_ptr<PathBuffer> path_buffer_;
std::shared_ptr<PathBuffer> path_buffer_;
std::shared_ptr<ObstacleManager> obstacle_manager_;
template <typename T>
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID&,