diff --git a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py index 27108054a..728a56811 100644 --- a/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py +++ b/bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_ball.py @@ -22,7 +22,7 @@ def __init__(self, blackboard, dsd, parameters): self.blocking = parameters.get("blocking", True) self.distance = parameters.get("distance", self.blackboard.config["ball_approach_dist"]) # Offset so we kick the ball with one foot instead of the center between the feet - self.side_offset = parameters.get("side_offset", 0.05) + self.side_offset = parameters.get("side_offset", 0.08) def perform(self, reevaluate=False): pose_msg = self.blackboard.pathfinding.get_ball_goal(self.target, self.distance, self.side_offset) diff --git a/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml b/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml index 1d09c2233..d19474dbc 100644 --- a/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml +++ b/bitbots_behavior/bitbots_body_behavior/config/body_behavior.yaml @@ -61,7 +61,7 @@ body_behavior: # An area in which the ball can be kicked # defined by min/max x/y values in meters which represent ball positions relative to base_footprint # http://www.ros.org/reps/rep-0103.html#axis-orientation - kick_x_enter: 0.25 + kick_x_enter: 0.23 kick_x_leave: 0.25 kick_y_enter: 0.12 kick_y_leave: 0.12 @@ -146,7 +146,7 @@ body_behavior: dribble_ball_distance_threshold: 0.5 dribble_kick_angle: 0.6 - kick_decision_smoothing: 1.0 + kick_decision_smoothing: 10.0 ################## # costmap params # diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml index 2fa51de3d..061aca8a4 100644 --- a/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml +++ b/bitbots_misc/bitbots_extrinsic_calibration/config/jack.yaml @@ -7,5 +7,5 @@ /bitbots_extrinsic_imu_calibration: ros__parameters: offset_x: 0.06 - offset_y: -0.085 + offset_y: -0.0 offset_z: 0.0 diff --git a/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml b/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml index bca74efee..5fdb160a2 100644 --- a/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml +++ b/bitbots_misc/bitbots_extrinsic_calibration/config/rory.yaml @@ -6,6 +6,6 @@ /bitbots_extrinsic_imu_calibration: ros__parameters: - offset_x: 0.0 - offset_y: 0.017 + offset_x: -0.03 + offset_y: -0.06 offset_z: 0.0 diff --git a/bitbots_misc/bitbots_parameter_blackboard/launch/parameter_blackboard.launch b/bitbots_misc/bitbots_parameter_blackboard/launch/parameter_blackboard.launch index 763a9607b..3631f568d 100644 --- a/bitbots_misc/bitbots_parameter_blackboard/launch/parameter_blackboard.launch +++ b/bitbots_misc/bitbots_parameter_blackboard/launch/parameter_blackboard.launch @@ -1,7 +1,7 @@ - + diff --git a/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml b/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml index c821b3bbe..777c2c682 100644 --- a/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml +++ b/bitbots_navigation/bitbots_path_planning/config/path_planning_parameters.yaml @@ -56,7 +56,7 @@ bitbots_path_planning: bounds<>: [0, 100] max_rotation_vel: type: double - default_value: 0.6 + default_value: 0.4 description: 'The maximum rotation velocity of the robot in rad/s around the z-axis' validation: bounds<>: [0.0, 1.0] @@ -98,13 +98,13 @@ bitbots_path_planning: bounds<>: [0.0, 1.0] translation_slow_down_factor: type: double - default_value: 1.0 + default_value: 0.6 description: 'Clamped p gain of the translation controller' validation: bounds<>: [0.0, 1.0] orient_to_goal_distance: type: double - default_value: 0.4 + default_value: 0.5 description: 'Distance at which we switch from orienting towards the path to orienting towards the goal poses orientation (in meters)' validation: bounds<>: [0.0, 10.0]