Add global path planner #12
@ -109,6 +109,7 @@ namespace mg {
|
|||||||
rclcpp::Rate rate(UPDATE_RATE);
|
rclcpp::Rate rate(UPDATE_RATE);
|
||||||
|
|
||||||
while (target_check() && rclcpp::ok()) {
|
while (target_check() && rclcpp::ok()) {
|
||||||
|
target_update();
|
||||||
if (hgoal->is_canceling()) {
|
if (hgoal->is_canceling()) {
|
||||||
cancel();
|
cancel();
|
||||||
return;
|
return;
|
||||||
|
|||||||
@ -22,7 +22,7 @@ namespace mg {
|
|||||||
|
|
||||||
template <>
|
template <>
|
||||||
inline void DWA<MgNavigationServer::MoveGlobal>::target_update() {
|
inline void DWA<MgNavigationServer::MoveGlobal>::target_update() {
|
||||||
baseNode.path_buffer()->update_path(goal);
|
baseNode.path_buffer()->update_path();
|
||||||
target_pos = baseNode.path_buffer()->get_next(pos, LOOKAHEAD);
|
target_pos = baseNode.path_buffer()->get_next(pos, LOOKAHEAD);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@ -47,6 +47,7 @@ namespace mg {
|
|||||||
resp_ = client_->async_send_request(req).share();
|
resp_ = client_->async_send_request(req).share();
|
||||||
}
|
}
|
||||||
if (resp_.valid()) {
|
if (resp_.valid()) {
|
||||||
|
|
||||||
path_msg_ = resp_.get();
|
path_msg_ = resp_.get();
|
||||||
auto req = std::make_shared<PathService::Request>();
|
auto req = std::make_shared<PathService::Request>();
|
||||||
req->x = goal_->x;
|
req->x = goal_->x;
|
||||||
@ -68,6 +69,7 @@ namespace mg {
|
|||||||
resp_ = client_->async_send_request(req).share();
|
resp_ = client_->async_send_request(req).share();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
resp_.wait();
|
||||||
path_msg_ = resp_.get();
|
path_msg_ = resp_.get();
|
||||||
auto req = std::make_shared<PathService::Request>();
|
auto req = std::make_shared<PathService::Request>();
|
||||||
req->x = goal_->x;
|
req->x = goal_->x;
|
||||||
|
|||||||
@ -12,6 +12,7 @@
|
|||||||
#include "tf2_ros/buffer.h"
|
#include "tf2_ros/buffer.h"
|
||||||
#include "tf2_ros/transform_listener.h"
|
#include "tf2_ros/transform_listener.h"
|
||||||
|
|
||||||
|
#include "mg_msgs/msg/path.hpp"
|
||||||
#include "mg_msgs/srv/calc_path.hpp"
|
#include "mg_msgs/srv/calc_path.hpp"
|
||||||
|
|
||||||
#define TREE_SIZE 9
|
#define TREE_SIZE 9
|
||||||
@ -30,6 +31,7 @@ namespace mg {
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
rclcpp::Service<mg_msgs::srv::CalcPath>::SharedPtr astar_service;
|
rclcpp::Service<mg_msgs::srv::CalcPath>::SharedPtr astar_service;
|
||||||
|
rclcpp::Publisher<mg_msgs::msg::Path>::SharedPtr path_pub_;
|
||||||
|
|
||||||
AStar astar_;
|
AStar astar_;
|
||||||
ObstacleManager obstacle_manager_;
|
ObstacleManager obstacle_manager_;
|
||||||
|
|||||||
@ -39,7 +39,7 @@ namespace mg {
|
|||||||
const glm::ivec2 grid_loc = IdToGrid(idx);
|
const glm::ivec2 grid_loc = IdToGrid(idx);
|
||||||
pq_tasks.pop();
|
pq_tasks.pop();
|
||||||
|
|
||||||
RCLCPP_INFO(node_->get_logger(), "Popped grid_loc: %d %d", grid_loc.x, grid_loc.y);
|
RCLCPP_DEBUG(node_->get_logger(), "Popped grid_loc: %d %d", grid_loc.x, grid_loc.y);
|
||||||
|
|
||||||
for (int i = 0; i < 4; i++) {
|
for (int i = 0; i < 4; i++) {
|
||||||
for (int j = 0; j < 9; j++) {
|
for (int j = 0; j < 9; j++) {
|
||||||
|
|||||||
@ -35,9 +35,14 @@ mg::PlannerNode::PlannerNode() : Node("planner"), astar_(this) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
astar_.execute(get_pos(), std::move(goals), resp->indicies);
|
astar_.execute(get_pos(), std::move(goals), resp->indicies);
|
||||||
|
mg_msgs::msg::Path path;
|
||||||
|
path.indicies = resp->indicies;
|
||||||
|
path_pub_->publish(path);
|
||||||
RCLCPP_INFO(get_logger(), "Handled request in %lf seconds", (get_clock()->now() - elapsed).seconds());
|
RCLCPP_INFO(get_logger(), "Handled request in %lf seconds", (get_clock()->now() - elapsed).seconds());
|
||||||
});
|
});
|
||||||
|
|
||||||
|
path_pub_ = create_publisher<mg_msgs::msg::Path>("/GeneratedPath", rclcpp::QoS(4).keep_last(2));
|
||||||
|
|
||||||
tf_buf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
|
tf_buf_ = std::make_shared<tf2_ros::Buffer>(get_clock());
|
||||||
tf_listener = std::make_shared<tf2_ros::TransformListener>(*tf_buf_);
|
tf_listener = std::make_shared<tf2_ros::TransformListener>(*tf_buf_);
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user