24#include <angles/angles.h>
25#include <tf2/transform_datatypes.h>
28#include <boost/assign.hpp>
29#include <boost/range/adaptor/reversed.hpp>
30#include <boost/range/algorithm/copy.hpp>
32#include <nav_2d_utils/tf_help.hpp>
33#include <nav_msgs/msg/path.hpp>
34#include <pluginlib/class_list_macros.hpp>
35#include <rclcpp/rclcpp.hpp>
40namespace forward_global_planner
52 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
53 const std::shared_ptr<tf2_ros::Buffer> tf,
54 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
61 RCLCPP_INFO(
nh_->get_logger(),
"[Forward Global Planner] initializing");
62 planPub_ =
nh_->create_publisher<nav_msgs::msg::Path>(
"global_plan", 1);
74 nav_msgs::msg::Path planMsg;
80 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal)
82 RCLCPP_INFO(
nh_->get_logger(),
"[Forward Global Planner] planning");
86 geometry_msgs::msg::PoseStamped transformedStart;
87 nav_2d_utils::transformPose(
tf_,
costmap_ros_->getGlobalFrameID(), start, transformedStart, ttol);
88 transformedStart.header.frame_id =
costmap_ros_->getGlobalFrameID();
90 geometry_msgs::msg::PoseStamped transformedGoal;
91 nav_2d_utils::transformPose(
tf_,
costmap_ros_->getGlobalFrameID(), goal, transformedGoal, ttol);
92 transformedGoal.header.frame_id =
costmap_ros_->getGlobalFrameID();
95 nav_msgs::msg::Path planMsg;
96 std::vector<geometry_msgs::msg::PoseStamped> plan;
103 double dx = transformedGoal.pose.position.x - transformedStart.pose.position.x;
104 double dy = transformedGoal.pose.position.y - transformedStart.pose.position.y;
106 double length = sqrt(dx * dx + dy * dy);
108 geometry_msgs::msg::PoseStamped prevState;
113 double heading_direction = atan2(dy, dx);
123 prevState = transformedStart;
127 double goalOrientation = angles::normalize_angle(tf2::getYaw(transformedGoal.pose.orientation));
129 planMsg.poses = plan;
130 planMsg.header.stamp = this->
nh_->now();
131 planMsg.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
134 nh_->get_logger(),
"[Forward Global Planner] generated plan size: " << plan.size());
137 bool acceptedGlobalPlan =
true;
140 nh_->get_logger(),
"[Forward Global Planner] checking obstacles in the generated plan");
141 nav2_costmap_2d::Costmap2D * costmap2d = this->
costmap_ros_->getCostmap();
142 for (
auto & p : plan)
145 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
146 auto cost = costmap2d->getCost(mx, my);
153 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
156 nh_->get_logger(),
"[Forward Global Planner] pose " << p.pose.position.x <<
", "
158 <<
" rejected, cost: " << cost);
159 acceptedGlobalPlan =
false;
164 if (acceptedGlobalPlan)
167 nh_->get_logger(),
"[Forward Global Planner] accepted plan: " << plan.size());
173 RCLCPP_INFO(
nh_->get_logger(),
"[Forward Global Planner] plan rejected");
174 planMsg.poses.clear();
184PLUGINLIB_EXPORT_CLASS(
double puresSpinningRadStep_
virtual void deactivate()
Method to deactivate planner and any threads involved in execution.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
virtual void cleanup()
Method to cleanup resources used on shutdown.
virtual ~ForwardGlobalPlanner()
Virtual destructor.
virtual nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal)
Method create the plan from a starting and ending goal.
rclcpp_lifecycle::LifecycleNode::SharedPtr nh_
double transform_tolerance_
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used
virtual void activate()
Method to active planner and any threads involved in execution.
double skip_straight_motion_distance_
std::shared_ptr< tf2_ros::Buffer > tf_
geometry_msgs::msg::PoseStamped makePureSpinningSubPlan(const geometry_msgs::msg::PoseStamped &start, double dstRads, std::vector< geometry_msgs::msg::PoseStamped > &plan, double radstep=0.005)
geometry_msgs::msg::PoseStamped makePureStraightSubPlan(const geometry_msgs::msg::PoseStamped &startOrientedPose, const geometry_msgs::msg::Point &goal, double length, std::vector< geometry_msgs::msg::PoseStamped > &plan)