29 FTCPlanner::FTCPlanner()
36 local_plan_publisher_ = private_nh.
advertise<nav_msgs::Path>(
"local_plan", 1);
37 costmap_ros_ = costmap_ros;
39 first_setPlan_ =
true;
40 rotate_to_global_plan_ =
false;
41 goal_reached_ =
false;
42 stand_at_goal_ =
false;
43 cmd_vel_angular_z_rotate_ = 0;
44 cmd_vel_linear_x_ = 0;
45 cmd_vel_angular_z_ = 0;
48 dsrv_ =
new dynamic_reconfigure::Server<FTCPlannerConfig>(private_nh);
49 dynamic_reconfigure::Server<FTCPlannerConfig>::CallbackType cb = boost::bind(&FTCPlanner::reconfigureCB,
this, _1, _2);
50 dsrv_->setCallback(cb);
54 ROS_INFO(
"FTCPlanner: Version 2 Init.");
57 void FTCPlanner::reconfigureCB(FTCPlannerConfig &config, uint32_t level)
59 if (config.restore_defaults)
61 config = default_config_;
62 config.restore_defaults =
false;
67 bool FTCPlanner::setPlan(
const std::vector<geometry_msgs::PoseStamped>& plan)
72 bool first_use =
false;
75 if(config_.join_obstacle){
77 joinCostmap_->initialize(costmap_ros_, global_costmap_ros_);
80 first_setPlan_ =
false;
87 if(std::abs(std::abs(old_goal_pose_.getOrigin().getX())-std::abs(goal_pose_.getOrigin().getX())) <= config_.position_accuracy &&
88 std::abs(std::abs(old_goal_pose_.getOrigin().getY())-std::abs(goal_pose_.getOrigin().getY())) <= config_.position_accuracy && !first_use
91 ROS_DEBUG(
"FTCPlanner: Old Goal == new Goal.");
96 rotate_to_global_plan_ =
true;
97 goal_reached_ =
false;
98 stand_at_goal_ =
false;
99 ROS_INFO(
"FTCPlanner: New Goal. Start new routine.");
102 old_goal_pose_ = goal_pose_;
107 bool FTCPlanner::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
113 costmap_ros_->getRobotPose(current_pose);
116 if(config_.join_obstacle){
117 joinCostmap_->joinMaps();
121 if(rotate_to_global_plan_)
123 double angle_to_global_plan = calculateGlobalPlanAngle(current_pose, global_plan_, checkMaxDistance(current_pose));
124 rotate_to_global_plan_ = rotateToOrientation(angle_to_global_plan, cmd_vel, 0.1);
130 double distance = sqrt(pow((goal_pose_.getOrigin().getX()-current_pose.getOrigin().getX()),2)+pow((goal_pose_.getOrigin().getY()-current_pose.getOrigin().getY()),2));
133 if(distance > config_.position_accuracy && !stand_at_goal_)
136 if(fabs(calculateGlobalPlanAngle(current_pose, global_plan_, checkMaxDistance(current_pose)) > 1.2))
138 ROS_INFO(
"FTCPlanner: Excessive deviation from global plan orientation. Start routine new.");
139 rotate_to_global_plan_ =
true;
142 max_point = driveToward(current_pose, cmd_vel);
144 if(!checkCollision(max_point))
154 ROS_INFO(
"FTCPlanner: Stand at goal. Rotate to goal orientation.");
156 stand_at_goal_ =
true;
162 if(!rotateToOrientation(angle_to_global_plan, cmd_vel, config_.rotation_accuracy))
164 goal_reached_ =
true;
166 cmd_vel.linear.x = 0;
167 cmd_vel.linear.y = 0;
171 publishPlan(max_point);
175 ROS_DEBUG(
"FTCPlanner: Calculation time: %f seconds", duration.
toSec());
183 transformed_global_plan_.clear();
184 for (
unsigned int i = 0; i < global_plan_.size(); i++)
187 double distance = sqrt(pow((x_pose.getOrigin().getX()-current_pose.getOrigin().getX()),2)+pow((x_pose.getOrigin().getY()-current_pose.getOrigin().getY()),2));
191 costmap_ros_->getGlobalFrameID());
192 geometry_msgs::PoseStamped pose;
194 transformed_global_plan_.push_back(pose);
198 if(distance > (config_.max_x_vel*config_.sim_time))
212 int max_point = points;
214 for(
int i = max_point; i >= 0; i--)
216 angle = calculateGlobalPlanAngle(current_pose, global_plan_, i);
220 if(fabs(angle) < config_.max_rotation_vel*config_.sim_time)
228 double FTCPlanner::calculateGlobalPlanAngle(
tf::Stamped<tf::Pose> current_pose,
const std::vector<geometry_msgs::PoseStamped>& plan,
int point)
230 if(point >= (
int)plan.size())
232 point = plan.size()-1;
235 double current_th =
tf::getYaw(current_pose.getRotation());
236 for(
int i = 0; i <= point; i++)
238 geometry_msgs::PoseStamped x_pose;
239 x_pose=transformed_global_plan_.at(i);
242 double angle_to_goal = atan2(x_pose.pose.position.y - current_pose.getOrigin().getY(),
243 x_pose.pose.position.x - current_pose.getOrigin().getX());
244 angle += angle_to_goal;
248 angle = angle/(point+1);
253 bool FTCPlanner::rotateToOrientation(
double angle, geometry_msgs::Twist& cmd_vel,
double accuracy)
256 if((cmd_vel_linear_x_ - 0.1) >= 0){
257 cmd_vel.linear.x = cmd_vel_linear_x_ - 0.1;
258 cmd_vel_linear_x_ = cmd_vel_linear_x_ - 0.1;
260 if(fabs(angle) > accuracy)
263 if(config_.max_rotation_vel >= fabs(angle) * (config_.acceleration_z+config_.slow_down_factor))
268 if(cmd_vel_angular_z_rotate_ >= -config_.min_rotation_vel)
270 cmd_vel_angular_z_rotate_ = - config_.min_rotation_vel;
271 cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
276 cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ + config_.acceleration_z/config_.local_planner_frequence;
277 cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
282 if(cmd_vel_angular_z_rotate_ <= config_.min_rotation_vel)
284 cmd_vel_angular_z_rotate_ = config_.min_rotation_vel;
285 cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
290 cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ - config_.acceleration_z/config_.local_planner_frequence;
291 cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
298 if(fabs(cmd_vel_angular_z_rotate_) < config_.max_rotation_vel)
303 cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ - config_.acceleration_z/config_.local_planner_frequence;
305 if(fabs(cmd_vel_angular_z_rotate_) > config_.max_rotation_vel)
307 cmd_vel_angular_z_rotate_ = - config_.max_rotation_vel;
309 cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
313 cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ + config_.acceleration_z/config_.local_planner_frequence;
315 if(fabs(cmd_vel_angular_z_rotate_) > config_.max_rotation_vel)
317 cmd_vel_angular_z_rotate_ = config_.max_rotation_vel;
320 cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
325 cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
328 ROS_DEBUG(
"FTCPlanner: cmd_vel.z: %f, angle: %f", cmd_vel.angular.z, angle);
333 cmd_vel_angular_z_rotate_ = 0;
334 cmd_vel.angular.z = 0;
346 max_point = checkMaxDistance(current_pose);
347 max_point = checkMaxAngle(max_point, current_pose);
350 double cmd_vel_linear_x_old = cmd_vel_linear_x_;
351 double cmd_vel_angular_z_old = cmd_vel_angular_z_;
353 geometry_msgs::PoseStamped x_pose;
354 x_pose = transformed_global_plan_.at(max_point);
356 distance = sqrt(pow((x_pose.pose.position.x-current_pose.getOrigin().getX()),2)+pow((x_pose.pose.position.y-current_pose.getOrigin().getY()),2));
357 angle = calculateGlobalPlanAngle(current_pose, global_plan_, max_point);
360 if((distance/config_.sim_time) > config_.max_x_vel)
362 cmd_vel_linear_x_ = config_.max_x_vel;
366 cmd_vel_linear_x_ = (distance/config_.sim_time);
370 if(fabs(angle/config_.sim_time)>config_.max_rotation_vel)
372 cmd_vel_angular_z_ = config_.max_rotation_vel;
376 cmd_vel_angular_z_ = (angle/config_.sim_time);
380 if(cmd_vel_linear_x_ > cmd_vel_linear_x_old+config_.acceleration_x/config_.local_planner_frequence)
382 cmd_vel_linear_x_ = cmd_vel_linear_x_old+config_.acceleration_x/config_.local_planner_frequence;
386 if(cmd_vel_linear_x_ < cmd_vel_linear_x_old-config_.acceleration_x/config_.local_planner_frequence)
388 cmd_vel_linear_x_ = cmd_vel_linear_x_old-config_.acceleration_x/config_.local_planner_frequence;
392 cmd_vel_linear_x_ = cmd_vel_linear_x_old;
397 if(fabs(cmd_vel_angular_z_) > fabs(cmd_vel_angular_z_old)+fabs(config_.acceleration_z/config_.local_planner_frequence))
399 if(cmd_vel_angular_z_ < 0)
401 cmd_vel_angular_z_ = cmd_vel_angular_z_old-config_.acceleration_z/config_.local_planner_frequence;
405 cmd_vel_angular_z_ = cmd_vel_angular_z_old+config_.acceleration_z/config_.local_planner_frequence;
409 if(cmd_vel_angular_z_ < 0 && cmd_vel_angular_z_old > 0)
411 if( fabs(cmd_vel_angular_z_ - cmd_vel_angular_z_old) > fabs(config_.acceleration_z/config_.local_planner_frequence))
413 cmd_vel_angular_z_ = cmd_vel_angular_z_old - config_.acceleration_z/config_.local_planner_frequence;
417 if(cmd_vel_angular_z_ > 0 && cmd_vel_angular_z_old < 0)
419 if( fabs(cmd_vel_angular_z_ - cmd_vel_angular_z_old) > fabs(config_.acceleration_z/config_.local_planner_frequence))
421 cmd_vel_angular_z_ = cmd_vel_angular_z_old + config_.acceleration_z/config_.local_planner_frequence;
426 if(cmd_vel_angular_z_ > config_.max_rotation_vel)
428 cmd_vel_angular_z_ = config_.max_rotation_vel;
430 if(cmd_vel_angular_z_ < -config_.max_rotation_vel)
432 cmd_vel_angular_z_ = (- config_.max_rotation_vel);
434 if(cmd_vel_linear_x_ > config_.max_x_vel)
436 cmd_vel_linear_x_ = config_.max_x_vel;
439 cmd_vel.linear.x = cmd_vel_linear_x_;
440 cmd_vel.angular.z = cmd_vel_angular_z_;
441 cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_;
442 ROS_DEBUG(
"FTCPlanner: max_point: %d, distance: %f, x_vel: %f, rot_vel: %f, angle: %f", max_point, distance, cmd_vel.linear.x, cmd_vel.angular.z, angle);
448 bool FTCPlanner::isGoalReached()
452 ROS_INFO(
"FTCPlanner: Goal reached.");
454 return goal_reached_;
457 bool FTCPlanner::checkCollision(
int max_points)
460 unsigned char previous_cost = 255;
462 for (
int i = 0; i <= max_points; i++)
464 geometry_msgs::PoseStamped x_pose;
465 x_pose = transformed_global_plan_.at(i);
469 costmap_ros_->getCostmap()->worldToMap(x_pose.pose.position.x, x_pose.pose.position.y, x, y);
470 unsigned char costs = costmap_ros_->getCostmap()->getCost(x, y);
474 if(!rotate_to_global_plan_)
476 ROS_INFO(
"FTCPlanner: Obstacel detected. Start routine new.");
478 rotate_to_global_plan_ =
true;
481 if(costs > 127 && costs > previous_cost)
483 ROS_WARN(
"FTCPlanner: Possible collision. Stop local planner.");
487 previous_cost = costs;
492 void FTCPlanner::publishPlan(
int max_point)
494 std::vector<geometry_msgs::PoseStamped> path;
495 path = transformed_global_plan_;
502 nav_msgs::Path gui_path;
503 gui_path.poses.resize(path.size());
504 gui_path.header.frame_id = path[0].header.frame_id;
505 gui_path.header.stamp = path[0].header.stamp;
508 for(
unsigned int i=0; i < path.size(); i++)
510 gui_path.poses[i] = path[i];
513 local_plan_publisher_.publish(gui_path);
516 FTCPlanner::~FTCPlanner()
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
static double getYaw(const Quaternion &bt_q)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double distance(double x0, double y0, double x1, double y1)
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getXPose(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, tf::Stamped< tf::Pose > &goal_pose, int plan_point)
Returns X pose in plan.
def shortest_angular_distance(from_angle, to_angle)