ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
There are 2 main different localplanners in the ROS navigation stack, called trajectory_planner_ros and dwa_local_planner. Make sure to know which one you are using.
A parameter like acc_lim_x will be used for projecting trajectories in the future. Given acc_lim_th: 0.05, one such trajectory will e.g. have these velocities in its points: 0, 0.05, 0.10, 0.15, 0.20 So the acceleration limit between two points are respected. However (and I personally consider this a design flaw), what is used as a drive command then is the final velocity of that trajectory, 0.20. The rationale is that lower level components (or hardware) will cap the velocities to what the robot can/should maximally do.
The parameter names should be the same in config yaml and dynamic reconfigure. However, the parameter names differ between trajectory_planner_ros and dwa_local_planner (Also a design flaw, for historic reasons). So if you observe different parameter names in dynamic reconfigure, maybe you are using dwa_local_planner.
rotation speed/acc should be configurable with the parameters as 'theta' values.
Also consider this page for help: http://www.ros.org/wiki/navigation/Tutorials/Navigation%20Tuning%20Guide
2 | No.2 Revision |
There are 2 main different localplanners in the ROS navigation stack, called trajectory_planner_ros and dwa_local_planner. Make sure to know which one you are using.
A parameter like acc_lim_x will be used for projecting trajectories in the future. Given acc_lim_th: 0.05, one such trajectory will would e.g. have these velocities in its points:
0, 0.05, 0.10, 0.15, 0.20
(if the time between points were 1s, I use this just for keeping the numbers simple)
So the acceleration limit between two points are respected.
However (and I personally consider this a design flaw), what is used as a drive command then is the final velocity of that trajectory, 0.20. The rationale is that lower level components (or hardware) will cap the velocities to what the robot can/should maximally do.
The parameter names should be the same in config yaml and dynamic reconfigure. However, the parameter names differ between trajectory_planner_ros and dwa_local_planner (Also a design flaw, for historic reasons). So if you observe different parameter names in dynamic reconfigure, maybe you are using dwa_local_planner.
rotation speed/acc should be configurable with the parameters as 'theta' values.
Also consider this page for help: http://www.ros.org/wiki/navigation/Tutorials/Navigation%20Tuning%20Guide
3 | No.3 Revision |
There are 2 main different localplanners in the ROS navigation stack, called trajectory_planner_ros and dwa_local_planner. Make sure to know which one you are using.
A parameter like acc_lim_x will be used for projecting trajectories in the future. Given acc_lim_th: 0.05, one such trajectory would e.g. have these velocities in its points: 0, 0.05, 0.10, 0.15, 0.20 (if the time between points were 1s, I use this just for keeping the numbers simple) So the acceleration limit between two points are respected. However (and I personally consider this a design flaw), what is used as a drive command then is the final velocity of that trajectory, 0.20. The rationale is that lower level components (or hardware) will cap the velocities to what the robot can/should maximally do.
The parameter names should be the same in config yaml and dynamic reconfigure. However, the parameter names differ between trajectory_planner_ros and dwa_local_planner (Also a design flaw, for historic reasons). So if you observe different parameter names in dynamic reconfigure, maybe you are using dwa_local_planner.
rotation speed/acc should be configurable with the parameters as 'theta' values.
Also consider this page for help: http://www.ros.org/wiki/navigation/Tutorials/Navigation%20Tuning%20Guide
[Edit after question has be extended:]
To check what local planner you are using, you can check at runtime using
$ rosparam get base_local_planner
The value may set in one of your launch files, with an entry like this:
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
With no such entry, move_base will by default use the trajectory_planner_ros. The dwa parameter you use is different, it allows to run trajectory_planner_ros to run similar to somewhat similar, but not the same, as dwa_planner_ros.
To debug you can display the costmap, local and global plan in rviz, see: http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack
Else to debug you'd have to add logging statements to trajectory_planner.cpp, in particular in createTrajectories, findBestPath and generate trajectory. This requires you to install the navigation stack from source.
In findBestPath you should find lines like:
tf::Vector3 start(best.xv_, best.yv_, 0);
drive_velocities.setOrigin(start);
tf::Matrix3x3 matrix;
matrix.setRotation(tf::createQuaternionFromYaw(best.thetav_));
This is where you can change the values by hand.
However, the dwa_planner_ros code is cleaner and should be easier to work with than the trajectory_planner_ros code.