SMACC2
Loading...
Searching...
No Matches
cl_nav2z::forward_global_planner::ForwardGlobalPlanner Class Reference

#include <forward_global_planner.hpp>

Inheritance diagram for cl_nav2z::forward_global_planner::ForwardGlobalPlanner:
Inheritance graph
Collaboration diagram for cl_nav2z::forward_global_planner::ForwardGlobalPlanner:
Collaboration graph

Public Types

using Ptr = std::shared_ptr<ForwardGlobalPlanner>
 

Public Member Functions

 ForwardGlobalPlanner ()
 
virtual ~ForwardGlobalPlanner ()
 Virtual destructor.
 
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
 
virtual void cleanup ()
 Method to cleanup resources used on shutdown.
 
virtual void activate ()
 Method to active planner and any threads involved in execution.
 
virtual void deactivate ()
 Method to deactivate planner and any threads involved in execution.
 
virtual nav_msgs::msg::Path createPlan (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
 Method create the plan from a starting and ending goal.
 

Private Attributes

rclcpp_lifecycle::LifecycleNode::SharedPtr nh_
 
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
 
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
 stored but almost not used
 
double skip_straight_motion_distance_
 
double puresSpinningRadStep_
 
std::string name_
 
double transform_tolerance_
 
std::shared_ptr< tf2_ros::Buffer > tf_
 

Detailed Description

Definition at line 34 of file forward_global_planner.hpp.

Member Typedef Documentation

◆ Ptr

Constructor & Destructor Documentation

◆ ForwardGlobalPlanner()

cl_nav2z::forward_global_planner::ForwardGlobalPlanner::ForwardGlobalPlanner ( )

◆ ~ForwardGlobalPlanner()

cl_nav2z::forward_global_planner::ForwardGlobalPlanner::~ForwardGlobalPlanner ( )
virtual

Virtual destructor.

Definition at line 49 of file forward_global_planner.cpp.

49{}

Member Function Documentation

◆ activate()

void cl_nav2z::forward_global_planner::ForwardGlobalPlanner::activate ( )
virtual

Method to active planner and any threads involved in execution.

Definition at line 70 of file forward_global_planner.cpp.

70{ planPub_->on_activate(); }
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_

References planPub_.

◆ cleanup()

void cl_nav2z::forward_global_planner::ForwardGlobalPlanner::cleanup ( )
virtual

Method to cleanup resources used on shutdown.

Definition at line 68 of file forward_global_planner.cpp.

68{}

◆ configure()

void cl_nav2z::forward_global_planner::ForwardGlobalPlanner::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
Parameters
parentpointer to user's node
nameThe name of this planner
tfA pointer to a TF buffer
costmap_rosA pointer to the costmap

Definition at line 51 of file forward_global_planner.cpp.

55{
56 nh_ = parent.lock();
57 tf_ = tf;
58 name_ = name;
59 costmap_ros_ = costmap_ros;
60
61 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] initializing");
62 planPub_ = nh_->create_publisher<nav_msgs::msg::Path>("global_plan", rclcpp::QoS(1));
63 skip_straight_motion_distance_ = 0.2; // meters
64 puresSpinningRadStep_ = 1000; // rads
66}
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros_
stored but almost not used

References costmap_ros_, name_, nh_, planPub_, puresSpinningRadStep_, skip_straight_motion_distance_, tf_, and transform_tolerance_.

◆ createPlan()

nav_msgs::msg::Path cl_nav2z::forward_global_planner::ForwardGlobalPlanner::createPlan ( const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal,
std::function< bool()> cancel_checker )
overridevirtual

Method create the plan from a starting and ending goal.

Parameters
startThe starting pose of the robot
goalThe goal pose of the robot
cancel_checkerFunction to check if planning should be cancelled
Returns
The sequence of poses to get from start to goal, if any

Definition at line 79 of file forward_global_planner.cpp.

82{
83 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] planning");
84
85 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
86
87 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] getting start and goal poses");
88 //---------------------------------------------------------------------
89 geometry_msgs::msg::PoseStamped transformedStart;
90 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), start, transformedStart, ttol);
91 transformedStart.header.frame_id = costmap_ros_->getGlobalFrameID();
92 //---------------------------------------------------------------------
93 geometry_msgs::msg::PoseStamped transformedGoal;
94 nav_2d_utils::transformPose(tf_, costmap_ros_->getGlobalFrameID(), goal, transformedGoal, ttol);
95 transformedGoal.header.frame_id = costmap_ros_->getGlobalFrameID();
96 //---------------------------------------------------------------------
97
98 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] creating plan vector");
99 nav_msgs::msg::Path planMsg;
100 std::vector<geometry_msgs::msg::PoseStamped> plan;
101
102 // three stages: 1 - heading to goal position, 2 - going forward keep orientation, 3 - heading to goal orientation
103
104 // 1 - heading to goal position
105 // orientation direction
106
107 double dx = transformedGoal.pose.position.x - transformedStart.pose.position.x;
108 double dy = transformedGoal.pose.position.y - transformedStart.pose.position.y;
109
110 double length = sqrt(dx * dx + dy * dy);
111
112 geometry_msgs::msg::PoseStamped prevState;
114 {
115 // skip initial pure spinning and initial straight motion
116 RCLCPP_INFO(nh_->get_logger(), "1 - heading to goal position pure spinning");
117 double heading_direction = atan2(dy, dx);
119 transformedStart, heading_direction, plan, puresSpinningRadStep_);
120
121 // RCLCPP_INFO(nh_->get_logger(), "2 - going forward keep orientation pure straight");
122 prevState =
123 cl_nav2z::makePureStraightSubPlan(prevState, transformedGoal.pose.position, length, plan);
124 }
125 else
126 {
127 prevState = transformedStart;
128 }
129
130 RCLCPP_INFO(nh_->get_logger(), "3 - heading to goal orientation");
131 double goalOrientation = angles::normalize_angle(tf2::getYaw(transformedGoal.pose.orientation));
132 cl_nav2z::makePureSpinningSubPlan(prevState, goalOrientation, plan, puresSpinningRadStep_);
133 planMsg.poses = plan;
134 planMsg.header.stamp = this->nh_->now();
135 planMsg.header.frame_id = this->costmap_ros_->getGlobalFrameID();
136
137 RCLCPP_INFO_STREAM(
138 nh_->get_logger(), "[Forward Global Planner] generated plan size: " << plan.size());
139
140 // check plan rejection
141 bool acceptedGlobalPlan = true;
142
143 RCLCPP_INFO(
144 nh_->get_logger(), "[Forward Global Planner] checking obstacles in the generated plan");
145 nav2_costmap_2d::Costmap2D * costmap2d = this->costmap_ros_->getCostmap();
146 for (auto & p : plan)
147 {
148 unsigned int mx, my;
149 costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
150 auto cost = costmap2d->getCost(mx, my);
151
152 // static const unsigned char NO_INFORMATION = 255;
153 // static const unsigned char LETHAL_OBSTACLE = 254;
154 // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
155 // static const unsigned char FREE_SPACE = 0;
156
157 if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
158 {
159 RCLCPP_INFO_STREAM(
160 nh_->get_logger(), "[Forward Global Planner] pose " << p.pose.position.x << ", "
161 << p.pose.position.y
162 << " rejected, cost: " << cost);
163 acceptedGlobalPlan = false;
164 break;
165 }
166 }
167
168 if (acceptedGlobalPlan)
169 {
170 RCLCPP_INFO_STREAM(
171 nh_->get_logger(), "[Forward Global Planner] accepted plan: " << plan.size());
172 planPub_->publish(planMsg);
173 return planMsg;
174 }
175 else
176 {
177 RCLCPP_INFO(nh_->get_logger(), "[Forward Global Planner] plan rejected");
178 planMsg.poses.clear();
179 planPub_->publish(planMsg);
180 return planMsg;
181 }
182}
geometry_msgs::msg::PoseStamped makePureSpinningSubPlan(const geometry_msgs::msg::PoseStamped &start, double dstRads, std::vector< geometry_msgs::msg::PoseStamped > &plan, double radstep=0.005)
Definition common.cpp:37
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)
Definition common.cpp:93

References costmap_ros_, cl_nav2z::makePureSpinningSubPlan(), cl_nav2z::makePureStraightSubPlan(), nh_, planPub_, puresSpinningRadStep_, skip_straight_motion_distance_, tf_, and transform_tolerance_.

Here is the call graph for this function:

◆ deactivate()

void cl_nav2z::forward_global_planner::ForwardGlobalPlanner::deactivate ( )
virtual

Method to deactivate planner and any threads involved in execution.

Definition at line 72 of file forward_global_planner.cpp.

73{
74 nav_msgs::msg::Path planMsg;
75 planPub_->publish(planMsg);
76 planPub_->on_deactivate();
77}

References planPub_.

Member Data Documentation

◆ costmap_ros_

std::shared_ptr<nav2_costmap_2d::Costmap2DROS> cl_nav2z::forward_global_planner::ForwardGlobalPlanner::costmap_ros_
private

stored but almost not used

Definition at line 90 of file forward_global_planner.hpp.

Referenced by configure(), and createPlan().

◆ name_

std::string cl_nav2z::forward_global_planner::ForwardGlobalPlanner::name_
private

Definition at line 96 of file forward_global_planner.hpp.

Referenced by configure().

◆ nh_

rclcpp_lifecycle::LifecycleNode::SharedPtr cl_nav2z::forward_global_planner::ForwardGlobalPlanner::nh_
private

Definition at line 85 of file forward_global_planner.hpp.

Referenced by configure(), and createPlan().

◆ planPub_

std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path> > cl_nav2z::forward_global_planner::ForwardGlobalPlanner::planPub_
private

Definition at line 87 of file forward_global_planner.hpp.

Referenced by activate(), configure(), createPlan(), and deactivate().

◆ puresSpinningRadStep_

double cl_nav2z::forward_global_planner::ForwardGlobalPlanner::puresSpinningRadStep_
private

Definition at line 94 of file forward_global_planner.hpp.

Referenced by configure(), createPlan(), and ForwardGlobalPlanner().

◆ skip_straight_motion_distance_

double cl_nav2z::forward_global_planner::ForwardGlobalPlanner::skip_straight_motion_distance_
private

Definition at line 92 of file forward_global_planner.hpp.

Referenced by configure(), createPlan(), and ForwardGlobalPlanner().

◆ tf_

std::shared_ptr<tf2_ros::Buffer> cl_nav2z::forward_global_planner::ForwardGlobalPlanner::tf_
private

Definition at line 100 of file forward_global_planner.hpp.

Referenced by configure(), and createPlan().

◆ transform_tolerance_

double cl_nav2z::forward_global_planner::ForwardGlobalPlanner::transform_tolerance_
private

Definition at line 98 of file forward_global_planner.hpp.

Referenced by configure(), and createPlan().


The documentation for this class was generated from the following files: