SMACC
Loading...
Searching...
No Matches
Public Member Functions | Private Member Functions | Private Attributes | List of all members
cl_move_base_z::forward_local_planner::ForwardLocalPlanner Class Reference

#include <forward_local_planner.h>

Inheritance diagram for cl_move_base_z::forward_local_planner::ForwardLocalPlanner:
Inheritance graph
Collaboration diagram for cl_move_base_z::forward_local_planner::ForwardLocalPlanner:
Collaboration graph

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_
 

Detailed Description

Definition at line 22 of file forward_local_planner.h.

Constructor & Destructor Documentation

◆ ForwardLocalPlanner()

cl_move_base_z::forward_local_planner::ForwardLocalPlanner::ForwardLocalPlanner ( )

ForwardLocalPlanner()

Definition at line 27 of file forward_local_planner.cpp.

28{
29}

◆ ~ForwardLocalPlanner()

cl_move_base_z::forward_local_planner::ForwardLocalPlanner::~ForwardLocalPlanner ( )
virtual

ForwardLocalPlanner()

Definition at line 36 of file forward_local_planner.cpp.

37{
38}

Member Function Documentation

◆ computeNewPositions()

Eigen::Vector3f cl_move_base_z::forward_local_planner::ForwardLocalPlanner::computeNewPositions ( const Eigen::Vector3f &  pos,
const Eigen::Vector3f &  vel,
double  dt 
)
private

Definition at line 143 of file forward_local_planner.cpp.

144{
145 Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();
146 new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;
147 new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;
148 new_pos[2] = pos[2] + vel[2] * dt;
149 return new_pos;
150}

Referenced by generateTrajectory().

Here is the caller graph for this function:

◆ computeVelocityCommands()

bool cl_move_base_z::forward_local_planner::ForwardLocalPlanner::computeVelocityCommands ( geometry_msgs::Twist &  cmd_vel)
overridevirtual

Given the current position, orientation, and velocity of the robot: compute velocity commands to send to the robot mobile base.

Parameters
cmd_velWill be filled with the velocity command to be passed to the robot base
Returns
True if a valid velocity command was found, false otherwise

computeVelocityCommands()

Definition at line 261 of file forward_local_planner.cpp.

262{
263 goalReached_ = false;
264 ROS_DEBUG("[ForwardLocalPlanner] ----- COMPUTE VELOCITY COMMAND LOCAL PLANNER ---");
265
266 tf::Stamped<tf::Pose> tfpose = optionalRobotPose(costmapRos_);
267
268 geometry_msgs::PoseStamped currentPose;
269 tf::poseStampedTFToMsg(tfpose,currentPose);
270 ROS_DEBUG_STREAM("[ForwardLocalPlanner] current robot pose " << currentPose);
271
272
273 bool ok = false;
274 while (!ok)
275 {
276 // iterate the point from the current position and ahead until reaching a new goal point in the path
277 while (!ok && currentPoseIndex_ < plan_.size())
278 {
279 auto &pose = plan_[currentPoseIndex_];
280 const geometry_msgs::Point &p = pose.pose.position;
281 tf::Quaternion q;
282 tf::quaternionMsgToTF(pose.pose.orientation, q);
283
284 // take error from the current position to the path point
285 double dx = p.x - tfpose.getOrigin().x();
286 double dy = p.y - tfpose.getOrigin().y();
287 double dist = sqrt(dx * dx + dy * dy);
288
289 double pangle = tf::getYaw(q);
290 double angle = tf::getYaw(tfpose.getRotation());
291 double angular_error = angles::shortest_angular_distance(pangle, angle);
292
293 if (dist >= carrot_distance_ || fabs(angular_error) > 0.1)
294 {
295 // the target pose is enough different to be defined as a target
296 ok = true;
297 ROS_DEBUG("current index: %d, carrot goal percentaje: %lf, dist: %lf, maxdist: %lf, angle_error: %lf", currentPoseIndex_, 100.0 * currentPoseIndex_ / plan_.size(), dist, carrot_distance_, angular_error);
298 }
299 else
300 {
302 }
303 }
304
305 ROS_DEBUG_STREAM("[ForwardLocalPlanner] selected carrot pose index " << currentPoseIndex_ << "/" << plan_.size());
306
307 if (currentPoseIndex_ >= plan_.size())
308 {
309 // even the latest point is quite similar, then take the last since it is the final goal
310 cmd_vel.linear.x = 0;
311 cmd_vel.angular.z = 0;
312 //ROS_INFO("End Local planner");
313 ok = true;
314 currentPoseIndex_ = plan_.size() - 1;
315 //return true;
316 }
317 }
318
319 //ROS_INFO("pose control algorithm");
320
321 const geometry_msgs::PoseStamped &finalgoalpose = plan_.back();
322 const geometry_msgs::PoseStamped &carrot_goalpose = plan_[currentPoseIndex_];
323 const geometry_msgs::Point &goalposition = carrot_goalpose.pose.position;
324
325 tf::Quaternion carrotGoalQ;
326 tf::quaternionMsgToTF(carrot_goalpose.pose.orientation, carrotGoalQ);
327 //ROS_INFO_STREAM("Plan goal quaternion at "<< goalpose.pose.orientation);
328
329 //goal orientation (global frame)
330 double betta = tf::getYaw(carrot_goalpose.pose.orientation) + betta_offset_;
331
332 double dx = goalposition.x - tfpose.getOrigin().x();
333 double dy = goalposition.y - tfpose.getOrigin().y();
334
335 //distance error to the targetpoint
336 double rho_error = sqrt(dx * dx + dy * dy);
337
338 //current angle
339 tf::Quaternion currentOrientation = tfpose.getRotation();
340 double theta = tf::getYaw(currentOrientation);
341 double alpha = atan2(dy, dx);
342 alpha = alpha + alpha_offset_;
343
344 double alpha_error = angles::shortest_angular_distance(alpha, theta);
345 double betta_error = angles::shortest_angular_distance(betta, theta);
346
347 double vetta; // = k_rho_ * rho_error;
348 double gamma; //= k_alpha_ * alpha_error + k_betta_ * betta_error;
349
350 if (rho_error > xy_goal_tolerance_) // reguular control rule, be careful, rho error is with the carrot not with the final goal (this is something to improve like the backwards planner)
351 {
352 vetta = k_rho_ * rho_error;
353 gamma = k_alpha_ * alpha_error;
354 }
355 else if (fabs(betta_error) >= yaw_goal_tolerance_) // pureSpining
356 {
357 vetta = 0;
358 gamma = k_betta_ * betta_error;
359 }
360 else // goal reached
361 {
362 ROS_DEBUG("GOAL REACHED");
363 vetta = 0;
364 gamma = 0;
365 goalReached_ = true;
366 }
367
368 // linear speed clamp
369 if (vetta > max_linear_x_speed_)
370 {
371 vetta = max_linear_x_speed_;
372 }
373 else if (vetta < -max_linear_x_speed_)
374 {
375 vetta = -max_linear_x_speed_;
376 }
377
378 // angular speed clamp
379 if (gamma > max_angular_z_speed_)
380 {
381 gamma = max_angular_z_speed_;
382 }
383 else if (gamma < -max_angular_z_speed_)
384 {
385 gamma = -max_angular_z_speed_;
386 }
387
388 cmd_vel.linear.x = vetta;
389 cmd_vel.angular.z = gamma;
390
391 //clamp(cmd_vel, max_linear_x_speed_, max_angular_z_speed_);
392
393 //ROS_INFO_STREAM("Local planner: "<< cmd_vel);
394
395 publishGoalMarker(goalposition.x, goalposition.y, betta);
396
397 ROS_DEBUG_STREAM("Forward local planner," << std::endl
398 << " theta: " << theta << std::endl
399 << " betta: " << betta << std::endl
400 << " err_x: " << dx << std::endl
401 << " err_y:" << dy << std::endl
402 << " rho_error:" << rho_error << std::endl
403 << " alpha_error:" << alpha_error << std::endl
404 << " betta_error:" << betta_error << std::endl
405 << " vetta:" << vetta << std::endl
406 << " gamma:" << gamma << std::endl
407 << " xy_goal_tolerance:" << xy_goal_tolerance_ << std::endl
408 << " yaw_goal_tolerance:" << yaw_goal_tolerance_ << std::endl);
409
410 //if(cmd_vel.linear.x==0 && cmd_vel.angular.z == 0 )
411 //{
412 //}
413
414 //integrate trajectory and check collision
415
416 tf::Stamped<tf::Pose> global_pose = optionalRobotPose(costmapRos_);
417
418 //->getRobotPose(global_pose);
419
420 auto *costmap2d = costmapRos_->getCostmap();
421 auto yaw = tf::getYaw(global_pose.getRotation());
422
423 auto &pos = global_pose.getOrigin();
424
425 Eigen::Vector3f currentpose(pos.x(), pos.y(), yaw);
426 Eigen::Vector3f currentvel(cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
427 std::vector<Eigen::Vector3f> trajectory;
428 this->generateTrajectory(currentpose, currentvel, 0.8 /*meters*/, M_PI / 8 /*rads*/, 3.0 /*seconds*/, 0.05 /*seconds*/, trajectory);
429
430 // check plan rejection
431 bool aceptedplan = true;
432
433 uint32_t mx, my;
434
435 int i = 0;
436 // ROS_INFO_STREAM("lplanner goal: " << finalgoalpose.pose.position);
437 for (auto &p : trajectory)
438 {
439 float dx = p[0] - finalgoalpose.pose.position.x;
440 float dy = p[1] - finalgoalpose.pose.position.y;
441
442 float dst = sqrt(dx * dx + dy * dy);
443 if (dst < xy_goal_tolerance_)
444 {
445 // ROS_INFO("trajectory checking skipped, goal reached");
446 break;
447 }
448
449 costmap2d->worldToMap(p[0], p[1], mx, my);
450 uint64_t cost = costmap2d->getCost(mx, my);
451
452 // ROS_INFO("checking cost pt %d [%lf, %lf] cell[%d,%d] = %d", i, p[0], p[1], mx, my, cost);
453 // ROS_INFO_STREAM("cost: " << cost);
454
455 // static const unsigned char NO_INFORMATION = 255;
456 // static const unsigned char LETHAL_OBSTACLE = 254;
457 // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
458 // static const unsigned char FREE_SPACE = 0;
459
460 if (costmap2d->getCost(mx, my) >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
461 {
462 aceptedplan = false;
463 // ROS_WARN("ABORTED LOCAL PLAN BECAUSE OBSTACLE DETEDTED");
464 break;
465 }
466 i++;
467 }
468
469 if (aceptedplan)
470 {
471 waiting_ = false;
472 return true;
473 }
474 else
475 {
476 // stop and wait
477 cmd_vel.linear.x = 0;
478 cmd_vel.angular.z = 0;
479
480 if (waiting_ == false)
481 {
482 waiting_ = true;
483 waitingStamp_ = ros::Time::now();
484 }
485 else
486 {
487 auto waitingduration = ros::Time::now() - waitingStamp_;
488
489 if (waitingduration > this->waitingTimeout_)
490 {
491 return false;
492 }
493 }
494
495 return true;
496 }
497}
void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector< Eigen::Vector3f > &outtraj)
tf::Stamped< tf::Pose > optionalRobotPose(costmap_2d::Costmap2DROS *costmapRos)

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_.

Here is the call graph for this function:

◆ generateTrajectory()

void cl_move_base_z::forward_local_planner::ForwardLocalPlanner::generateTrajectory ( const Eigen::Vector3f &  pos,
const Eigen::Vector3f &  vel,
float  maxdist,
float  maxangle,
float  maxtime,
float  dt,
std::vector< Eigen::Vector3f > &  outtraj 
)
private

Definition at line 81 of file forward_local_planner.cpp.

82{
83 //simulate the trajectory and check for collisions, updating costs along the way
84 bool end = false;
85 float time = 0;
86 Eigen::Vector3f currentpos = pos;
87 int i = 0;
88 while (!end)
89 {
90 //add the point to the trajectory so we can draw it later if we want
91 //traj.addPoint(pos[0], pos[1], pos[2]);
92
93 // if (continued_acceleration_) {
94 // //calculate velocities
95 // loop_vel = computeNewVelocities(sample_target_vel, loop_vel, limits_->getAccLimits(), dt);
96 // //ROS_WARN_NAMED("Generator", "Flag: %d, Loop_Vel %f, %f, %f", continued_acceleration_, loop_vel[0], loop_vel[1], loop_vel[2]);
97 // }
98
99 auto loop_vel = vel;
100 //update the position of the robot using the velocities passed in
101 auto newpos = computeNewPositions(currentpos, loop_vel, dt);
102
103 auto dx = newpos[0] - currentpos[0];
104 auto dy = newpos[1] - currentpos[1];
105 float dist, angledist;
106
107 //ROS_INFO("traj point %d", i);
108 dist = sqrt(dx * dx + dy * dy);
109 if (dist > maxdist)
110 {
111 end = true;
112 //ROS_INFO("dist break: %f", dist);
113 }
114 else
115 {
116 // ouble from, double to
117 angledist = fabs(angles::shortest_angular_distance(currentpos[2], newpos[2]));
118 if (angledist > maxanglediff)
119 {
120 end = true;
121 //ROS_INFO("angle dist break: %f", angledist);
122 }
123 else
124 {
125 outtraj.push_back(newpos);
126
127 time += dt;
128 if (time > maxtime)
129 {
130 end = true;
131 //ROS_INFO("time break: %f", time);
132 }
133
134 //ROS_INFO("dist: %f, angledist: %f, time: %f", dist, angledist, time);
135 }
136 }
137
138 currentpos = newpos;
139 i++;
140 } // end for simulation steps
141}
Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)

References computeNewPositions().

Referenced by computeVelocityCommands().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ initialize() [1/3]

void cl_move_base_z::forward_local_planner::ForwardLocalPlanner::initialize ( )

Definition at line 40 of file forward_local_planner.cpp.

41{
42 k_rho_ = 1.0;
43 k_alpha_ = -0.4;
44 k_betta_ = -1.0; // set to zero means that orientation is not important
45 //k_betta_ = 1.0;
46 //betta_offset_=0;
47
48 goalReached_ = false;
49 carrot_distance_ = 0.4;
50
51 ros::NodeHandle private_nh("~");
52
54
55 ros::NodeHandle nh("~/ForwardLocalPlanner");
56
57 nh.param("k_rho", k_rho_, k_rho_);
58 nh.param("k_alpha", k_alpha_, k_alpha_);
59 nh.param("k_betta", k_betta_, k_betta_);
60 nh.param("carrot_distance", carrot_distance_, carrot_distance_);
61
62 nh.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05);
63 nh.param("xy_goal_tolerance", xy_goal_tolerance_, 0.10);
64 nh.param("max_linear_x_speed", max_linear_x_speed_, 1.0);
65 nh.param("max_angular_z_speed", max_angular_z_speed_, 2.0);
66
67 ROS_INFO("[ForwardLocalPlanner] max linear speed: %lf, max angular speed: %lf, k_rho: %lf, carrot_distance: %lf, ", max_linear_x_speed_, max_angular_z_speed_, k_rho_, carrot_distance_);
68 goalMarkerPublisher_ = nh.advertise<visualization_msgs::MarkerArray>("goal_marker", 1);
69
70 waiting_ = false;
71 waitingTimeout_ = ros::Duration(10);
72 ROS_INFO("[ForwardLocalPlanner] initialized");
73}

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().

Here is the caller graph for this function:

◆ initialize() [2/3]

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().

Here is the call graph for this function:

◆ initialize() [3/3]

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.

Parameters
nameThe name to give this instance of the local planner
tfA pointer to a transform listener
costmap_rosThe cost map to use for assigning costs to local plans

initialize()

Definition at line 157 of file forward_local_planner.cpp.

158{
159 costmapRos_ = costmap_ros;
160 this->initialize();
161}

References costmapRos_, and initialize().

Here is the call graph for this function:

◆ isGoalReached()

bool cl_move_base_z::forward_local_planner::ForwardLocalPlanner::isGoalReached ( )
overridevirtual

Check if the goal pose has been achieved by the local planner.

Returns
True if achieved, false otherwise

isGoalReached()

Definition at line 504 of file forward_local_planner.cpp.

505{
506 return goalReached_;
507}

References goalReached_.

◆ publishGoalMarker()

void cl_move_base_z::forward_local_planner::ForwardLocalPlanner::publishGoalMarker ( double  x,
double  y,
double  phi 
)
private

publishGoalMarker()

Definition at line 168 of file forward_local_planner.cpp.

169{
170 visualization_msgs::Marker marker;
171
172 marker.header.frame_id = this->costmapRos_->getGlobalFrameID();
173 marker.header.stamp = ros::Time::now();
174 marker.ns = "my_namespace2";
175 marker.id = 0;
176 marker.type = visualization_msgs::Marker::ARROW;
177 marker.action = visualization_msgs::Marker::ADD;
178 marker.pose.orientation.w = 1;
179
180 marker.scale.x = 0.1;
181 marker.scale.y = 0.3;
182 marker.scale.z = 0.1;
183 marker.color.a = 1.0;
184 marker.color.r = 0;
185 marker.color.g = 0;
186 marker.color.b = 1.0;
187
188 geometry_msgs::Point start, end;
189 start.x = x;
190 start.y = y;
191
192 end.x = x + 0.5 * cos(phi);
193 end.y = y + 0.5 * sin(phi);
194
195 marker.points.push_back(start);
196 marker.points.push_back(end);
197
198 visualization_msgs::MarkerArray ma;
199 ma.markers.push_back(marker);
200
201 this->goalMarkerPublisher_.publish(ma);
202}

References costmapRos_, and goalMarkerPublisher_.

Referenced by computeVelocityCommands().

Here is the caller graph for this function:

◆ setPlan()

bool cl_move_base_z::forward_local_planner::ForwardLocalPlanner::setPlan ( const std::vector< geometry_msgs::PoseStamped > &  plan)
overridevirtual

Set the plan that the local planner is following.

Parameters
planThe plan to pass to the local planner
Returns
True if the plan was updated successfully, false otherwise

setPlan()

Definition at line 514 of file forward_local_planner.cpp.

515{
516 plan_ = plan;
517 goalReached_ = false;
518 return true;
519}

References goalReached_, and plan_.

Member Data Documentation

◆ alpha_offset_

const double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::alpha_offset_ = 0
private

Definition at line 74 of file forward_local_planner.h.

Referenced by computeVelocityCommands().

◆ betta_offset_

const double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::betta_offset_ = 0
private

Definition at line 75 of file forward_local_planner.h.

Referenced by computeVelocityCommands().

◆ carrot_angular_distance_

rad cl_move_base_z::forward_local_planner::ForwardLocalPlanner::carrot_angular_distance_
private

Definition at line 78 of file forward_local_planner.h.

◆ carrot_distance_

meter cl_move_base_z::forward_local_planner::ForwardLocalPlanner::carrot_distance_
private

Definition at line 77 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ costmapRos_

costmap_2d::Costmap2DROS* cl_move_base_z::forward_local_planner::ForwardLocalPlanner::costmapRos_
private

Definition at line 65 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), initialize(), and publishGoalMarker().

◆ currentPoseIndex_

int cl_move_base_z::forward_local_planner::ForwardLocalPlanner::currentPoseIndex_
private

Definition at line 90 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ goalMarkerPublisher_

ros::Publisher cl_move_base_z::forward_local_planner::ForwardLocalPlanner::goalMarkerPublisher_
private

Definition at line 67 of file forward_local_planner.h.

Referenced by initialize(), and publishGoalMarker().

◆ goalReached_

bool cl_move_base_z::forward_local_planner::ForwardLocalPlanner::goalReached_
private

◆ k_alpha_

double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::k_alpha_
private

Definition at line 70 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ k_betta_

double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::k_betta_
private

Definition at line 71 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ k_rho_

double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::k_rho_
private

Definition at line 69 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ max_angular_z_speed_

double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::max_angular_z_speed_
private

Definition at line 83 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ max_linear_x_speed_

double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::max_linear_x_speed_
private

Definition at line 84 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ plan_

std::vector<geometry_msgs::PoseStamped> cl_move_base_z::forward_local_planner::ForwardLocalPlanner::plan_
private

Definition at line 92 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and setPlan().

◆ waiting_

bool cl_move_base_z::forward_local_planner::ForwardLocalPlanner::waiting_
private

Definition at line 94 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ waitingStamp_

ros::Time cl_move_base_z::forward_local_planner::ForwardLocalPlanner::waitingStamp_
private

Definition at line 96 of file forward_local_planner.h.

Referenced by computeVelocityCommands().

◆ waitingTimeout_

ros::Duration cl_move_base_z::forward_local_planner::ForwardLocalPlanner::waitingTimeout_
private

Definition at line 95 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ xy_goal_tolerance_

double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::xy_goal_tolerance_
private

Definition at line 81 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().

◆ yaw_goal_tolerance_

double cl_move_base_z::forward_local_planner::ForwardLocalPlanner::yaw_goal_tolerance_
private

Definition at line 80 of file forward_local_planner.h.

Referenced by computeVelocityCommands(), and initialize().


The documentation for this class was generated from the following files: