SMACC2
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Private Attributes | List of all members
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)
 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 33 of file forward_global_planner.hpp.

Member Typedef Documentation

◆ Ptr

Definition at line 36 of file forward_global_planner.hpp.

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 
)
virtual

Method create the plan from a starting and ending goal.

Parameters
startThe starting pose of the robot
goalThe goal pose of the robot
Returns
The sequence of poses to get from start to goal, if any

Definition at line 79 of file forward_global_planner.cpp.

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

Referenced by configure(), and createPlan().


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