Skip to content
Snippets Groups Projects

Added a new parameter to generate the steer angle instead of the angular speed for the control.

Merged Sergi Hernandez requested to merge development into master
9 files
+ 172
104
Compare changes
  • Side-by-side
  • Inline
Files
9
@@ -40,55 +40,61 @@ from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
# Name Type Reconfiguration level Description Default Min Max
gen.add("max_sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 10, 0, 20)
gen.add("min_sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 1.7, 0, 10)
gen.add("sim_granularity", double_t, 0, "The granularity with which to check for collisions along each trajectory in meters", 0.025, 0)
gen.add("angular_sim_granularity", double_t, 0, "The granularity with which to check for collisions for rotations in radians", 0.1, 0)
gen.add("path_distance_bias", double_t, 0, "The weight for the path distance part of the cost function", 32.0, 0.0)
gen.add("goal_distance_bias", double_t, 0, "The weight for the goal distance part of the cost function", 24.0, 0.0)
gen.add("occdist_scale", double_t, 0, "The weight for the obstacle distance part of the cost function", 0.01, 0.0)
gen.add("stop_time_buffer", double_t, 0, "The amount of time that the robot must stop before a collision in order for a trajectory to be considered valid in seconds", 0.2, 0)
gen.add("oscillation_reset_dist", double_t, 0, "The distance the robot must travel before oscillation flags are reset, in meters", 0.05, 0)
gen.add("oscillation_reset_angle", double_t, 0, "The angle the robot must turn before oscillation flags are reset, in radians", 0.2, 0)
gen.add("forward_point_distance", double_t, 0, "The distance from the center point of the robot to place an additional scoring point, in meters", 0.325)
gen.add("scaling_speed", double_t, 0, "The absolute value of the velocity at which to start scaling the robot's footprint, in m/s", 0.25, 0)
gen.add("max_scaling_factor", double_t, 0, "The maximum factor to scale the robot's footprint by", 0.2, 0)
gen.add("trans_vel_samples", int_t, 0, "The number of samples to use when exploring the x velocity space", 3, 1)
gen.add("steer_angle_samples", int_t, 0, "The number of samples to use when exploring the y velocity space", 10, 1)
gen.add("prune_plan", bool_t, 0, "Start following closest point of global plan, not first point (if different).", False)
gen.add("xy_goal_tolerance", double_t, 0, "Within what maximum distance we consider the robot to be in goal", 0.1)
gen.add("yaw_goal_tolerance", double_t, 0, "Within what maximum angle difference we consider the robot to face goal direction", 0.1)
gen.add("trans_stopped_vel", double_t, 0, "Below what maximum velocity we consider the robot to be stopped in translation", 0.1)
gen.add("rot_stopped_vel", double_t, 0, "Below what maximum rotation velocity we consider the robot to be stopped in rotation", 0.1)
gen.add("restore_defaults", bool_t, 0, "Restore to the original configuration.", False)
gen.add("max_trans_vel", double_t, 0, "maximum translational speed", 0.3, 0, 20)
gen.add("min_trans_vel", double_t, 0, "minimum translational speed", -0.3, -20, 0)
gen.add("max_trans_acc", double_t, 0, "maximum translational acceleration", 1.0, 0, 20)
gen.add("max_steer_angle", double_t, 0, "maximum steer angle", 0.45, 0, 0.54)
gen.add("min_steer_angle", double_t, 0, "minimum steer angle", -0.45, -0.54, 0)
gen.add("max_steer_vel", double_t, 0, "maximum steer speed", 1.0, 0, 2)
gen.add("min_steer_vel", double_t, 0, "minimum steer speed", -1.0, -2, 0)
gen.add("max_steer_acc", double_t, 0, "maximum steer acceleration", 0.36, 0, 5)
gen.add("axis_distance", double_t, 0, "distance between axes", 1.65, -2.0, 2)
gen.add("wheel_distance", double_t, 0, "distance between wheels", 1.2, 0, 2)
gen.add("wheel_radius", double_t, 0, "Wheel diameter", 0.436, 0, 2)
gen.add("split_ignore_length", double_t, 0, "Paths segments under this length will be ignored",1.0,0.0,2.0)
gen.add("cmd_vel_avg", int_t, 0, "Number of cmd_vel to average", 1, 1, 20)
gen.add("odom_avg", int_t, 0, "Number of odom to average", 1, 1, 20)
gen.add("planner_patience", int_t, 0, "number of impossible paths before replanning",2, 0, 10)
gen.add("hdiff_scale", double_t, 0, "The weight for the heading distance part of the cost function", 1.0 ,0, 500)
gen.add("heading_points", int_t, 0, "The number of points to check the heading", 8, 1, 64)
# Name Type Reconfiguration level Description Default Min Max
gen.add("max_sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 10, 0, 20)
gen.add("min_sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 1.7, 0, 10)
gen.add("sim_granularity", double_t, 0, "The granularity with which to check for collisions along each trajectory in meters", 0.025, 0)
gen.add("angular_sim_granularity", double_t, 0, "The granularity with which to check for collisions for rotations in radians", 0.1, 0)
gen.add("path_distance_bias", double_t, 0, "The weight for the path distance part of the cost function", 32.0, 0.0)
gen.add("goal_distance_bias", double_t, 0, "The weight for the goal distance part of the cost function", 24.0, 0.0)
gen.add("occdist_scale", double_t, 0, "The weight for the obstacle distance part of the cost function", 0.01, 0.0)
gen.add("stop_time_buffer", double_t, 0, "The amount of time that the robot must stop before a collision in order for a trajectory to be considered valid in seconds", 0.2, 0)
gen.add("oscillation_reset_dist", double_t, 0, "The distance the robot must travel before oscillation flags are reset, in meters", 0.05, 0)
gen.add("oscillation_reset_angle", double_t, 0, "The angle the robot must turn before oscillation flags are reset, in radians", 0.2, 0)
gen.add("forward_point_distance", double_t, 0, "The distance from the center point of the robot to place an additional scoring point, in meters", 0.325)
gen.add("scaling_speed", double_t, 0, "The absolute value of the velocity at which to start scaling the robot's footprint, in m/s", 0.25, 0)
gen.add("max_scaling_factor", double_t, 0, "The maximum factor to scale the robot's footprint by", 0.2, 0)
gen.add("trans_vel_samples", int_t, 0, "The number of samples to use when exploring the x velocity space", 3, 1)
gen.add("steer_angle_samples", int_t, 0, "The number of samples to use when exploring the steer angle space", 10, 1)
gen.add("angular_vel_samples", int_t, 0, "The number of samples to use when exploring the angular velocity space", 10, 1)
gen.add("use_steer_angle_cmd", bool_t, 0, "Whether to use the steer angle or the angular velocity.", False)
gen.add("prune_plan", bool_t, 0, "Start following closest point of global plan, not first point (if different).", False)
gen.add("xy_goal_tolerance", double_t, 0, "Within what maximum distance we consider the robot to be in goal", 0.1)
gen.add("yaw_goal_tolerance", double_t, 0, "Within what maximum angle difference we consider the robot to face goal direction", 0.1)
gen.add("trans_stopped_vel", double_t, 0, "Below what maximum velocity we consider the robot to be stopped in translation", 0.1)
gen.add("rot_stopped_vel", double_t, 0, "Below what maximum rotation velocity we consider the robot to be stopped in rotation", 0.1)
gen.add("restore_defaults", bool_t, 0, "Restore to the original configuration.", False)
gen.add("max_trans_vel", double_t, 0, "maximum translational speed", 0.3, 0, 20)
gen.add("min_trans_vel", double_t, 0, "minimum translational speed", -0.3, -20, 0)
gen.add("max_trans_acc", double_t, 0, "maximum translational acceleration", 1.0, 0, 20)
gen.add("max_steer_angle", double_t, 0, "maximum steer angle", 0.45, 0, 0.54)
gen.add("min_steer_angle", double_t, 0, "minimum steer angle", -0.45, -0.54, 0)
gen.add("max_steer_vel", double_t, 0, "maximum steer speed", 1.0, 0, 2)
gen.add("min_steer_vel", double_t, 0, "minimum steer speed", -1.0, -2, 0)
gen.add("max_steer_acc", double_t, 0, "maximum steer acceleration", 0.36, 0, 5)
gen.add("max_angular_vel", double_t, 0, "maximum angular speed", 0.3, 0, 20)
gen.add("min_angular_vel", double_t, 0, "minimum angular speed", -0.3, -20, 0)
gen.add("axis_distance", double_t, 0, "distance between axes", 1.65, -2.0, 2)
gen.add("wheel_distance", double_t, 0, "distance between wheels", 1.2, 0, 2)
gen.add("wheel_radius", double_t, 0, "Wheel diameter", 0.436, 0, 2)
gen.add("use_trans_vel_deadzone", bool_t, 0, "Whether to use a deadzone in the translational velocity or not", False)
gen.add("trans_vel_deadzone", double_t, 0, "Translatinal velocity minimum value", 0.1, 0.01, 1.0)
gen.add("split_ignore_length", double_t, 0, "Paths segments under this length will be ignored", 1.0, 0.0, 2.0)
gen.add("cmd_vel_avg", int_t, 0, "Number of cmd_vel to average", 1, 1, 20)
gen.add("odom_avg", int_t, 0, "Number of odom to average", 1, 1, 20)
gen.add("planner_patience", int_t, 0, "number of impossible paths before replanning", 2, 0, 10)
gen.add("hdiff_scale", double_t, 0, "The weight for the heading distance part of the cost function", 1.0, 0, 500)
gen.add("heading_points", int_t, 0, "The number of points to check the heading", 8, 1, 64)
exit(gen.generate(PACKAGE, "AckermannLocalPlannerAlgorithm", "AckermannLocalPlanner"))
Loading