Created
May 20, 2025 12:04
-
-
Save Narukara/85615c9e381f49ebe1937f558744397e to your computer and use it in GitHub Desktop.
ackermann.patch
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
diff --git a/gz_ros2_control_demos/config/ackermann_drive_controller.yaml b/gz_ros2_control_demos/config/ackermann_drive_controller.yaml | |
index 71b96d9..94e6b93 100644 | |
--- a/gz_ros2_control_demos/config/ackermann_drive_controller.yaml | |
+++ b/gz_ros2_control_demos/config/ackermann_drive_controller.yaml | |
@@ -18,8 +18,8 @@ ackermann_steering_controller: | |
rear_wheels_radius: 0.3 | |
front_steering: true | |
reference_timeout: 2.0 | |
- rear_wheels_names: ['rear_left_wheel_joint', 'rear_right_wheel_joint'] | |
- front_wheels_names: ['left_wheel_steering_joint', 'right_wheel_steering_joint'] | |
+ rear_wheels_names: ['rear_right_wheel_joint', 'rear_left_wheel_joint'] | |
+ front_wheels_names: ['right_wheel_steering_joint', 'left_wheel_steering_joint'] | |
use_stamped_vel: true | |
open_loop: false | |
velocity_rolling_window_size: 10 | |
diff --git a/gz_ros2_control_demos/urdf/test_ackermann_drive.xacro.urdf b/gz_ros2_control_demos/urdf/test_ackermann_drive.xacro.urdf | |
index 825a383..b0cbb0c 100644 | |
--- a/gz_ros2_control_demos/urdf/test_ackermann_drive.xacro.urdf | |
+++ b/gz_ros2_control_demos/urdf/test_ackermann_drive.xacro.urdf | |
@@ -109,10 +109,10 @@ | |
</link> | |
<joint name="left_wheel_steering_joint" type="revolute"> | |
- <origin xyz="0.9 -0.5 -0.2" rpy="1.57 0 0" /> | |
+ <origin xyz="0.9 0.5 -0.2" rpy="0 0 0" /> | |
<parent link="chassis" /> | |
<child link="left_wheel_steering" /> | |
- <axis xyz="0 1 0" /> | |
+ <axis xyz="0 0 1" /> | |
<dynamics damping="0.2" /> | |
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="30"/> | |
</joint> | |
@@ -126,10 +126,10 @@ | |
</link> | |
<joint name="right_wheel_steering_joint" type="revolute"> | |
- <origin xyz="0.9 0.5 -0.2" rpy="1.57 0 0" /> | |
+ <origin xyz="0.9 -0.5 -0.2" rpy="0 0 0" /> | |
<parent link="chassis" /> | |
<child link="right_wheel_steering" /> | |
- <axis xyz="0 1 0" /> | |
+ <axis xyz="0 0 1" /> | |
<dynamics damping="0.2" /> | |
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="30"/> | |
</joint> | |
@@ -154,7 +154,7 @@ | |
</link> | |
<joint name="front_left_wheel_joint" type="continuous"> | |
- <origin xyz="0 0 0" rpy="0 0 0" /> | |
+ <origin xyz="0 0 0" rpy="-1.57 0 0" /> | |
<parent link="left_wheel_steering" /> | |
<child link="front_left_wheel" /> | |
<axis xyz="0 0 1" /> | |
@@ -181,7 +181,7 @@ | |
</link> | |
<joint name="front_right_wheel_joint" type="continuous"> | |
- <origin xyz="0 0 0" rpy="0 0 0" /> | |
+ <origin xyz="0 0 0" rpy="-1.57 0 0" /> | |
<parent link="right_wheel_steering" /> | |
<child link="front_right_wheel" /> | |
<axis xyz="0 0 1" /> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment