SMACC
|
#include <forward_local_planner.h>
Public Member Functions | |
ForwardLocalPlanner () | |
virtual | ~ForwardLocalPlanner () |
virtual bool | computeVelocityCommands (geometry_msgs::Twist &cmd_vel) override |
Given the current position, orientation, and velocity of the robot: compute velocity commands to send to the robot mobile base. More... | |
virtual bool | isGoalReached () override |
Check if the goal pose has been achieved by the local planner. More... | |
virtual bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &plan) override |
Set the plan that the local planner is following. More... | |
void | initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmapRos_) |
Constructs the local planner. More... | |
void | initialize (std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmapRos) |
void | initialize () |
Private Member Functions | |
void | publishGoalMarker (double x, double y, double phi) |
void | generateTrajectory (const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector< Eigen::Vector3f > &outtraj) |
Eigen::Vector3f | computeNewPositions (const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt) |
Private Attributes | |
costmap_2d::Costmap2DROS * | costmapRos_ |
ros::Publisher | goalMarkerPublisher_ |
double | k_rho_ |
double | k_alpha_ |
double | k_betta_ |
bool | goalReached_ |
const double | alpha_offset_ = 0 |
const double | betta_offset_ = 0 |
meter | carrot_distance_ |
rad | carrot_angular_distance_ |
double | yaw_goal_tolerance_ |
double | xy_goal_tolerance_ |
double | max_angular_z_speed_ |
double | max_linear_x_speed_ |
int | currentPoseIndex_ |
std::vector< geometry_msgs::PoseStamped > | plan_ |
bool | waiting_ |
ros::Duration | waitingTimeout_ |
ros::Time | waitingStamp_ |
Definition at line 22 of file forward_local_planner.h.
cl_move_base_z::forward_local_planner::ForwardLocalPlanner::ForwardLocalPlanner | ( | ) |
|
virtual |
|
private |
Definition at line 143 of file forward_local_planner.cpp.
Referenced by generateTrajectory().
|
overridevirtual |
Given the current position, orientation, and velocity of the robot: compute velocity commands to send to the robot mobile base.
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
Definition at line 261 of file forward_local_planner.cpp.
References alpha_offset_, betta_offset_, carrot_distance_, costmapRos_, currentPoseIndex_, generateTrajectory(), goalReached_, k_alpha_, k_betta_, k_rho_, max_angular_z_speed_, max_linear_x_speed_, cl_move_base_z::forward_local_planner::optionalRobotPose(), plan_, publishGoalMarker(), waiting_, waitingStamp_, waitingTimeout_, xy_goal_tolerance_, and yaw_goal_tolerance_.
|
private |
Definition at line 81 of file forward_local_planner.cpp.
References computeNewPositions().
Referenced by computeVelocityCommands().
void cl_move_base_z::forward_local_planner::ForwardLocalPlanner::initialize | ( | ) |
Definition at line 40 of file forward_local_planner.cpp.
References carrot_distance_, currentPoseIndex_, goalMarkerPublisher_, goalReached_, k_alpha_, k_betta_, k_rho_, max_angular_z_speed_, max_linear_x_speed_, waiting_, waitingTimeout_, xy_goal_tolerance_, and yaw_goal_tolerance_.
Referenced by initialize().
void cl_move_base_z::forward_local_planner::ForwardLocalPlanner::initialize | ( | std::string | name, |
tf2_ros::Buffer * | tf, | ||
costmap_2d::Costmap2DROS * | costmapRos | ||
) |
Definition at line 75 of file forward_local_planner.cpp.
References costmapRos_, and initialize().
void cl_move_base_z::forward_local_planner::ForwardLocalPlanner::initialize | ( | std::string | name, |
tf::TransformListener * | tf, | ||
costmap_2d::Costmap2DROS * | costmap_ros | ||
) |
Constructs the local planner.
name | The name to give this instance of the local planner |
tf | A pointer to a transform listener |
costmap_ros | The cost map to use for assigning costs to local plans |
Definition at line 157 of file forward_local_planner.cpp.
References costmapRos_, and initialize().
|
overridevirtual |
Check if the goal pose has been achieved by the local planner.
Definition at line 504 of file forward_local_planner.cpp.
References goalReached_.
|
private |
Definition at line 168 of file forward_local_planner.cpp.
References costmapRos_, and goalMarkerPublisher_.
Referenced by computeVelocityCommands().
|
overridevirtual |
Set the plan that the local planner is following.
plan | The plan to pass to the local planner |
Definition at line 514 of file forward_local_planner.cpp.
References goalReached_, and plan_.
|
private |
Definition at line 74 of file forward_local_planner.h.
Referenced by computeVelocityCommands().
|
private |
Definition at line 75 of file forward_local_planner.h.
Referenced by computeVelocityCommands().
|
private |
Definition at line 78 of file forward_local_planner.h.
|
private |
Definition at line 77 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 65 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), initialize(), and publishGoalMarker().
|
private |
Definition at line 90 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 67 of file forward_local_planner.h.
Referenced by initialize(), and publishGoalMarker().
|
private |
Definition at line 72 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), initialize(), isGoalReached(), and setPlan().
|
private |
Definition at line 70 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 71 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 69 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 83 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 84 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 92 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and setPlan().
|
private |
Definition at line 94 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 96 of file forward_local_planner.h.
Referenced by computeVelocityCommands().
|
private |
Definition at line 95 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 81 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().
|
private |
Definition at line 80 of file forward_local_planner.h.
Referenced by computeVelocityCommands(), and initialize().