127  const geometry_msgs::msg::Pose & pose, 
double r, 
double g, 
double b)
 
  129  double phi = tf2::getYaw(pose.orientation);
 
  130  visualization_msgs::msg::Marker marker;
 
  131  marker.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
 
  132  marker.header.stamp = 
nh_->now();
 
  133  marker.ns = 
"my_namespace2";
 
  135  marker.type = visualization_msgs::msg::Marker::ARROW;
 
  136  marker.action = visualization_msgs::msg::Marker::ADD;
 
  137  marker.lifetime = rclcpp::Duration(0s);
 
  138  marker.scale.x = 0.1;
 
  139  marker.scale.y = 0.3;
 
  140  marker.scale.z = 0.1;
 
  141  marker.color.a = 1.0;
 
  146  geometry_msgs::msg::Point start, end;
 
  147  start.x = pose.position.x;
 
  148  start.y = pose.position.y;
 
  150  end.x = pose.position.x + 0.5 * cos(phi);
 
  151  end.y = pose.position.y + 0.5 * sin(phi);
 
  153  marker.points.push_back(start);
 
  154  marker.points.push_back(end);
 
  156  visualization_msgs::msg::MarkerArray ma;
 
  157  ma.markers.push_back(marker);
 
 
  183  const geometry_msgs::msg::PoseStamped & start, 
const geometry_msgs::msg::PoseStamped & goal,
 
  184  std::vector<geometry_msgs::msg::PoseStamped> & plan)
 
  186  auto q = start.pose.orientation;
 
  188  geometry_msgs::msg::PoseStamped pose;
 
  191  double dx = start.pose.position.x - goal.pose.position.x;
 
  192  double dy = start.pose.position.y - goal.pose.position.y;
 
  194  double length = sqrt(dx * dx + dy * dy);
 
  196  geometry_msgs::msg::PoseStamped prevState;
 
  201      nh_->get_logger(), 
"1 - heading to goal position pure spinning radstep: %lf",
 
  203    double heading_direction = atan2(dy, dx);
 
  204    double startyaw = tf2::getYaw(q);
 
  205    double offset = angles::shortest_angular_distance(startyaw, heading_direction);
 
  206    heading_direction = startyaw + offset;
 
  210    RCLCPP_INFO(
nh_->get_logger(), 
"2 - going forward keep orientation pure straight");
 
  220    nh_->get_logger(), 
"[BackwardGlobalPlanner] backward global plan size:  " << plan.size());
 
 
  229  const geometry_msgs::msg::PoseStamped & start, 
const geometry_msgs::msg::PoseStamped & goal)
 
  232    nh_->get_logger(), 
"[BackwardGlobalPlanner] goal frame id: " 
  233                         << goal.header.frame_id << 
" pose: " << goal.pose.position);
 
  235    nh_->get_logger(), 
"[BackwardGlobalPlanner] goal pose frame id: " << goal.header.frame_id);
 
  239  geometry_msgs::msg::PoseStamped transformedStart;
 
  240  nav_2d_utils::transformPose(
tf_, 
costmap_ros_->getGlobalFrameID(), start, transformedStart, ttol);
 
  241  transformedStart.header.frame_id = 
costmap_ros_->getGlobalFrameID();
 
  243  geometry_msgs::msg::PoseStamped transformedGoal;
 
  244  nav_2d_utils::transformPose(
tf_, 
costmap_ros_->getGlobalFrameID(), goal, transformedGoal, ttol);
 
  245  transformedGoal.header.frame_id = 
costmap_ros_->getGlobalFrameID();
 
  248    nh_->get_logger(), 
"[BackwardGlobalPlanner] creating default backward global plan");
 
  250  std::vector<geometry_msgs::msg::PoseStamped> plan;
 
  253  RCLCPP_INFO_STREAM(
nh_->get_logger(), 
"[BackwardGlobalPlanner] publishing markers");
 
  256  nav_msgs::msg::Path planMsg;
 
  257  planMsg.poses = plan;
 
  258  planMsg.header.stamp = this->
nh_->now();
 
  259  planMsg.header.frame_id = this->
costmap_ros_->getGlobalFrameID();
 
  263  bool acceptedGlobalPlan = 
true;
 
  266    nh_->get_logger(), 
"[BackwardGlobalPlanner] checking backwards trajectory on costmap");
 
  268  for (
auto & p : plan)
 
  271    costmap2d->worldToMap(p.pose.position.x, p.pose.position.y, mx, my);
 
  272    auto cost = costmap2d->getCost(mx, my);
 
  278    if (cost >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
 
  282        "[BackwardGlobalPlanner] backwards plan is rejected because interscts the obstacle " 
  283        "inscribed inflated obstacle" 
  284          << 
" at: " << p.pose.position.x << 
" " << p.pose.position.y);
 
  290  if (!acceptedGlobalPlan)
 
  294      "[BackwardGlobalPlanner] backward plan request is not accepted, returning " 
  296    planMsg.poses.clear();
 
  300    nh_->get_logger(), 
"[BackwardGlobalPlanner] backward global plan publishing path. poses count: " 
  301                         << planMsg.poses.size());
 
 
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)