diff --git a/orange_bringup/config/motor_driver_params.yaml b/orange_bringup/config/motor_driver_params.yaml index bc42f1e..fa77064 100644 --- a/orange_bringup/config/motor_driver_params.yaml +++ b/orange_bringup/config/motor_driver_params.yaml @@ -25,10 +25,10 @@ motor_driver_node: set_decel_time_right: 200 # ms # Maximum rpm - max_left_rpm: 100 - max_right_rpm: 100 + max_left_rpm: 162 + max_right_rpm: 162 # Width of rpm to be regarded as 0 # If 3, then -3 to 3 is considered rpm 0 deadband_rpm: 3 - #Max speed = {max_rpm * (2pi/60)}*wheel_radius = 1.023m/s + #Max speed = {max_rpm * (2pi/60)}*wheel_radius = 1.656m/s = 5.962km/h diff --git a/orange_navigation/config/navigation2_params.yaml b/orange_navigation/config/navigation2_params.yaml index 4ea2078..de7a84c 100644 --- a/orange_navigation/config/navigation2_params.yaml +++ b/orange_navigation/config/navigation2_params.yaml @@ -133,11 +133,11 @@ controller_server: debug_trajectory_details: True min_vel_x: 0.0 min_vel_y: 0.0 - max_vel_x: 1.0 + max_vel_x: 1.6 max_vel_y: 0.0 max_vel_theta: 0.5 min_speed_xy: 0.0 - max_speed_xy: 1.0 + max_speed_xy: 1.6 min_speed_theta: 0.0 acc_lim_x: 0.5 acc_lim_y: 0.0 @@ -168,19 +168,19 @@ controller_server: Oscillation.x_only_threshold: 0.05 Oscillation.scale: 1.0 BaseObstacle.sum_scores: false - BaseObstacle.scale: 0.02 - GoalAlign.forward_point_distance: 0.1 + BaseObstacle.scale: 1.0 + GoalAlign.forward_point_distance: 0.325 GoalAlign.aggregation_type: "last" - GoalAlign.scale: 24.0 - PathAlign.forward_point_distance: 1.0 + GoalAlign.scale: 1.0 + PathAlign.forward_point_distance: 0.325 PathAlign.aggregation_type: "last" - PathAlign.scale: 50.0 + PathAlign.scale: 1.0 PathDist.aggregation_type: "last" - PathDist.scale: 32.0 + PathDist.scale: 1.0 GoalDist.aggregation_type: "last" - GoalDist.scale: 24.0 + GoalDist.scale: 1.0 ObstacleFootprint.sum_scores: false - ObstacleFootprint.scale: 32.0 + ObstacleFootprint.scale: 1.0 controller_server_rclcpp_node: ros__parameters: @@ -335,7 +335,7 @@ velocity_smoother: smoothing_frequency: 20.0 scale_velocities: False feedback: "OPEN_LOOP" - max_velocity: [1.0, 0.0, 1.0] + max_velocity: [1.6, 0.0, 0.5] min_velocity: [-1.0, 0.0, -1.0] max_accel: [0.5, 0.0, 0.5] max_decel: [-0.5, 0.0, -0.5]