24#include <geometry_msgs/msg/pose_stamped.hpp> 
   25#include <rclcpp/rclcpp.hpp> 
   30  const geometry_msgs::msg::PoseStamped & start, 
double dstRads,
 
   31  std::vector<geometry_msgs::msg::PoseStamped> & plan, 
double radstep = 0.005);
 
   34  const geometry_msgs::msg::PoseStamped & startOrientedPose, 
const geometry_msgs::msg::Point & goal,
 
   35  double length, std::vector<geometry_msgs::msg::PoseStamped> & plan);
 
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)