Added collision avoidance to MoveGlobal routine
This commit is contained in:
@ -6,7 +6,7 @@
|
||||
#include <rclcpp/client.hpp>
|
||||
#include <rclcpp/service.hpp>
|
||||
#include "mg_planner/a_star/a_star.hpp"
|
||||
#include "mg_planner/obstacleManager.hpp"
|
||||
#include "mg_obstacles/mg_obstacles.hpp"
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
#include "tf2_ros/buffer.h"
|
||||
@ -25,7 +25,7 @@ namespace mg {
|
||||
|
||||
void fill_obstacles() { }
|
||||
|
||||
ObstacleManager& getObstacleManager() { return obstacle_manager_; }
|
||||
ObstacleManager::SharedPtr getObstacleManager() { return obstacle_manager_; }
|
||||
|
||||
glm::ivec2 get_pos();
|
||||
|
||||
@ -33,8 +33,8 @@ namespace mg {
|
||||
rclcpp::Service<mg_msgs::srv::CalcPath>::SharedPtr astar_service;
|
||||
rclcpp::Publisher<mg_msgs::msg::Path>::SharedPtr path_pub_;
|
||||
|
||||
AStar astar_;
|
||||
ObstacleManager obstacle_manager_;
|
||||
AStar astar_;
|
||||
ObstacleManager::SharedPtr obstacle_manager_;
|
||||
|
||||
std::shared_ptr<tf2_ros::Buffer> tf_buf_;
|
||||
std::shared_ptr<tf2_ros::TransformListener> tf_listener;
|
||||
|
||||
@ -4,13 +4,5 @@
|
||||
#include <vector>
|
||||
|
||||
namespace mg {
|
||||
class ObstacleManager {
|
||||
const std::vector<glm::vec2> static_obstacles_;
|
||||
const std::vector<glm::vec2> permanent_obstacles_;
|
||||
|
||||
glm::vec2 dynamic_obstacle_;
|
||||
|
||||
public:
|
||||
bool check_collision(glm::ivec2 pos, float size);
|
||||
};
|
||||
bool check_collision(glm::ivec2 pos, float size);
|
||||
}
|
||||
Reference in New Issue
Block a user