Skip to content

Commit 7d3218d

Browse files
mergify[bot]Narukaraahcorde
authored
Fix ackermann demo (backport #582) (#583)
Signed-off-by: Alejandro Hernandez Cordero <ahcorde@gmail.com> Co-authored-by: Narukara <narukara17@gmail.com> Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent 28a3caa commit 7d3218d

File tree

2 files changed

+8
-8
lines changed

2 files changed

+8
-8
lines changed

gz_ros2_control_demos/config/ackermann_drive_controller.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,8 @@ ackermann_steering_controller:
1414
traction_wheels_radius: 0.3
1515
steering_wheels_radius: 0.3
1616
reference_timeout: 2.0 # In s. Timeout to stop if no cmd_vel is received
17-
traction_joints_names: ['rear_left_wheel_joint', 'rear_right_wheel_joint']
18-
steering_joints_names: ['left_wheel_steering_joint', 'right_wheel_steering_joint']
17+
traction_joints_names: ['rear_right_wheel_joint', 'rear_left_wheel_joint']
18+
steering_joints_names: ['right_wheel_steering_joint', 'left_wheel_steering_joint']
1919
open_loop: false
2020
velocity_rolling_window_size: 10
2121
base_frame_id: base_link

gz_ros2_control_demos/urdf/test_ackermann_drive.xacro.urdf

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -109,10 +109,10 @@
109109
</link>
110110

111111
<joint name="left_wheel_steering_joint" type="revolute">
112-
<origin xyz="0.9 -0.5 -0.2" rpy="1.57 0 0" />
112+
<origin xyz="0.9 0.5 -0.2" rpy="0 0 0" />
113113
<parent link="chassis" />
114114
<child link="left_wheel_steering" />
115-
<axis xyz="0 1 0" />
115+
<axis xyz="0 0 1" />
116116
<dynamics damping="0.2" />
117117
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="30"/>
118118
</joint>
@@ -126,10 +126,10 @@
126126
</link>
127127

128128
<joint name="right_wheel_steering_joint" type="revolute">
129-
<origin xyz="0.9 0.5 -0.2" rpy="1.57 0 0" />
129+
<origin xyz="0.9 -0.5 -0.2" rpy="0 0 0" />
130130
<parent link="chassis" />
131131
<child link="right_wheel_steering" />
132-
<axis xyz="0 1 0" />
132+
<axis xyz="0 0 1" />
133133
<dynamics damping="0.2" />
134134
<limit effort="1000.0" lower="-1.57" upper="1.57" velocity="30"/>
135135
</joint>
@@ -154,7 +154,7 @@
154154
</link>
155155

156156
<joint name="front_left_wheel_joint" type="continuous">
157-
<origin xyz="0 0 0" rpy="0 0 0" />
157+
<origin xyz="0 0 0" rpy="-1.57 0 0" />
158158
<parent link="left_wheel_steering" />
159159
<child link="front_left_wheel" />
160160
<axis xyz="0 0 1" />
@@ -181,7 +181,7 @@
181181
</link>
182182

183183
<joint name="front_right_wheel_joint" type="continuous">
184-
<origin xyz="0 0 0" rpy="0 0 0" />
184+
<origin xyz="0 0 0" rpy="-1.57 0 0" />
185185
<parent link="right_wheel_steering" />
186186
<child link="front_right_wheel" />
187187
<axis xyz="0 0 1" />

0 commit comments

Comments
 (0)