Add a-star based global planner
This commit is contained in:
@ -17,6 +17,8 @@
|
||||
#include "tf2_ros/transform_listener.h"
|
||||
#include "tf2_ros/buffer.h"
|
||||
|
||||
#include "path_buffer.hpp"
|
||||
|
||||
namespace mg {
|
||||
|
||||
namespace Geometry = geometry_msgs::msg;
|
||||
@ -25,12 +27,14 @@ namespace mg {
|
||||
public:
|
||||
RCLCPP_SMART_PTR_ALIASES_ONLY(MgNavigationServer)
|
||||
using MovePoint = mg_msgs::action::MovePoint;
|
||||
using MoveGlobal = mg_msgs::action::MoveGlobal;
|
||||
using MoveStraight = mg_msgs::action::MoveStraight;
|
||||
using LookAt = mg_msgs::action::LookAt;
|
||||
using Rotate = mg_msgs::action::Rotate;
|
||||
|
||||
rclcpp::Publisher<Geometry::TwistStamped>::SharedPtr pub_twist;
|
||||
|
||||
rclcpp_action::Server<MoveGlobal>::SharedPtr sv_move_global;
|
||||
rclcpp_action::Server<MovePoint>::SharedPtr sv_move_point;
|
||||
rclcpp_action::Server<MoveStraight>::SharedPtr sv_move_straight;
|
||||
rclcpp_action::Server<LookAt>::SharedPtr sv_look_at;
|
||||
@ -43,9 +47,13 @@ namespace mg {
|
||||
|
||||
MgNavigationServer(rclcpp::NodeOptions& opts);
|
||||
|
||||
std::shared_ptr<PathBuffer> path_buffer() { return path_buffer_; }
|
||||
|
||||
private:
|
||||
bool is_processing = false;
|
||||
|
||||
std::shared_ptr<PathBuffer> path_buffer_;
|
||||
|
||||
template <typename T>
|
||||
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID&,
|
||||
typename T::Goal::ConstSharedPtr,
|
||||
|
||||
Reference in New Issue
Block a user