Skip to content

Commit d70f39d

Browse files
committed
Set servo number coherent with airframe file
1 parent 8aeae4b commit d70f39d

File tree

1 file changed

+2
-4
lines changed

1 file changed

+2
-4
lines changed

models/lawnmower/model.sdf

+2-4
Original file line numberDiff line numberDiff line change
@@ -572,7 +572,6 @@
572572
</joint>
573573
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
574574
<joint_name>right_wheel_joint</joint_name>
575-
<!--sub_topic>servo_0</sub_topic-->
576575
<sub_topic>command/motor_speed</sub_topic>
577576
<use_actuator_msg>true</use_actuator_msg>
578577
<actuator_number>0</actuator_number>
@@ -589,7 +588,6 @@
589588
</plugin>
590589
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
591590
<joint_name>left_wheel_joint</joint_name>
592-
<!--sub_topic>servo_1</sub_topic-->
593591
<sub_topic>command/motor_speed</sub_topic>
594592
<use_actuator_msg>true</use_actuator_msg>
595593
<actuator_number>1</actuator_number>
@@ -607,15 +605,15 @@
607605
<!-- Note: SIM_GZ_SV_FAIL1 defines servo_0 etc. -->
608606
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
609607
<joint_name>cutter_blades_joint</joint_name>
610-
<sub_topic>servo_2</sub_topic>
608+
<sub_topic>servo_0</sub_topic>
611609
<!-- p_gain>1.0</p_gain>
612610
<cmd_max>2000.0</cmd_max>
613611
<cmd_min>1000.0</cmd_min>
614612
<cmd_offset>0.0</cmd_offset -->
615613
</plugin>
616614
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
617615
<joint_name>engine_visual_joint</joint_name>
618-
<sub_topic>servo_3</sub_topic>
616+
<sub_topic>servo_1</sub_topic>
619617
<p_gain>10.0</p_gain>
620618
<!-- use_actuator_msg>false</use_actuator_msg>
621619
<initial_velocity>0</initial_velocity>

0 commit comments

Comments
 (0)