#include <ftc_planner.h>
Definition at line 42 of file ftc_planner.h.
◆ FTCPlanner()
| ftc_local_planner::FTCPlanner::FTCPlanner |
( |
| ) |
|
◆ ~FTCPlanner()
| ftc_local_planner::FTCPlanner::~FTCPlanner |
( |
| ) |
|
◆ calculateGlobalPlanAngle()
| double ftc_local_planner::FTCPlanner::calculateGlobalPlanAngle |
( |
tf::Stamped< tf::Pose > |
current_pose, |
|
|
const std::vector< geometry_msgs::PoseStamped > & |
plan, |
|
|
int |
points |
|
) |
| |
|
private |
Calculate the orientation of the global plan.
- Parameters
-
| current | robot pose |
| global | plan |
| number | of points which used for calculation |
Definition at line 233 of file ftc_planner.cpp.
◆ checkCollision()
| bool ftc_local_planner::FTCPlanner::checkCollision |
( |
int |
max_points | ) |
|
|
private |
Check if the considerd points are in local collision.
- Parameters
-
| points | of global plan which are considerd. |
- Returns
- true if no collision.
Definition at line 462 of file ftc_planner.cpp.
◆ checkMaxAngle()
| int ftc_local_planner::FTCPlanner::checkMaxAngle |
( |
int |
points, |
|
|
tf::Stamped< tf::Pose > |
current_pose |
|
) |
| |
|
private |
Goes backward along global plan the max angle whith sim_time and max_rotation_vel allow.
- Parameters
-
| point | where starts to go backward |
| current | pose of the robot |
- Returns
- max point of the global plan with can reached
Definition at line 215 of file ftc_planner.cpp.
◆ checkMaxDistance()
Goes along global plan the max distance whith sim_time and max_x_vel allow.
- Parameters
-
- Returns
- max point of the global plan with can reached
Definition at line 184 of file ftc_planner.cpp.
◆ computeVelocityCommands()
| bool ftc_local_planner::FTCPlanner::computeVelocityCommands |
( |
geometry_msgs::Twist & |
cmd_vel | ) |
|
|
virtual |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
- Parameters
-
| cmd_vel | Will be filled with the velocity command to be passed to the robot base |
- Returns
- True if a valid velocity command was found, false otherwise
Implements nav_core::BaseLocalPlanner.
Definition at line 107 of file ftc_planner.cpp.
◆ driveToward()
| int ftc_local_planner::FTCPlanner::driveToward |
( |
tf::Stamped< tf::Pose > |
current_pose, |
|
|
geometry_msgs::Twist & |
cmd_vel |
|
) |
| |
|
private |
Drive along the global plan and calculate the velocity.
- Parameters
-
| current | pose of the robot |
| velocity | message |
- Returns
- number of points of global plan which are used
Definition at line 344 of file ftc_planner.cpp.
◆ initialize()
Constructs the local planner.
- Parameters
-
| name | The name to give this instance of the local planner |
| tf | A pointer to a transform buffer |
| costmap_ros | The cost map to use for assigning costs to local plans |
Implements nav_core::BaseLocalPlanner.
Definition at line 33 of file ftc_planner.cpp.
◆ isGoalReached()
| bool ftc_local_planner::FTCPlanner::isGoalReached |
( |
| ) |
|
|
virtual |
◆ publishPlan()
| void ftc_local_planner::FTCPlanner::publishPlan |
( |
int |
max_point | ) |
|
|
private |
Publish the global plan for visulatation.
- Parameters
-
| points | where jused to calculate plan. |
Definition at line 497 of file ftc_planner.cpp.
◆ reconfigureCB()
| void ftc_local_planner::FTCPlanner::reconfigureCB |
( |
FTCPlannerConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
◆ rotateToOrientation()
| bool ftc_local_planner::FTCPlanner::rotateToOrientation |
( |
double |
angle, |
|
|
geometry_msgs::Twist & |
cmd_vel, |
|
|
double |
accuracy |
|
) |
| |
|
private |
Rotation at place.
- Parameters
-
| angle | which is to rotate |
| velocity | message which is calculate for rotation |
| accuracy | of orientation |
- Returns
- true if rotate, false if rotation goal reached
Definition at line 258 of file ftc_planner.cpp.
◆ setPlan()
| bool ftc_local_planner::FTCPlanner::setPlan |
( |
const std::vector< geometry_msgs::PoseStamped > & |
plan | ) |
|
|
virtual |
Set the plan that the local planner is following.
- Parameters
-
| plan | The plan to pass to the local planner |
- Returns
- True if the plan was updated successfully, false otherwise
Implements nav_core::BaseLocalPlanner.
Definition at line 67 of file ftc_planner.cpp.
◆ cmd_vel_angular_z_
| double ftc_local_planner::FTCPlanner::cmd_vel_angular_z_ |
|
private |
◆ cmd_vel_angular_z_rotate_
| double ftc_local_planner::FTCPlanner::cmd_vel_angular_z_rotate_ |
|
private |
◆ cmd_vel_linear_x_
| double ftc_local_planner::FTCPlanner::cmd_vel_linear_x_ |
|
private |
◆ config_
| ftc_local_planner::FTCPlannerConfig ftc_local_planner::FTCPlanner::config_ |
|
private |
◆ costmap_ros_
◆ default_config_
| ftc_local_planner::FTCPlannerConfig ftc_local_planner::FTCPlanner::default_config_ |
|
private |
◆ dsrv_
| dynamic_reconfigure::Server<FTCPlannerConfig>* ftc_local_planner::FTCPlanner::dsrv_ |
|
private |
◆ first_setPlan_
| bool ftc_local_planner::FTCPlanner::first_setPlan_ |
|
private |
◆ global_plan_
| std::vector<geometry_msgs::PoseStamped> ftc_local_planner::FTCPlanner::global_plan_ |
|
private |
◆ goal_pose_
◆ goal_reached_
| bool ftc_local_planner::FTCPlanner::goal_reached_ |
|
private |
◆ joinCostmap_
| JoinCostmap* ftc_local_planner::FTCPlanner::joinCostmap_ |
|
private |
◆ local_plan_publisher_
◆ old_goal_pose_
◆ rotate_to_global_plan_
| bool ftc_local_planner::FTCPlanner::rotate_to_global_plan_ |
|
private |
◆ stand_at_goal_
| bool ftc_local_planner::FTCPlanner::stand_at_goal_ |
|
private |
◆ tf_
◆ transformed_global_plan_
| std::vector<geometry_msgs::PoseStamped> ftc_local_planner::FTCPlanner::transformed_global_plan_ |
|
private |
The documentation for this class was generated from the following files: