Skip to content

Commit

Permalink
Set servo number coherent with airframe file
Browse files Browse the repository at this point in the history
  • Loading branch information
Perrrewi committed Dec 11, 2024
1 parent 3d80b49 commit 3691e12
Showing 1 changed file with 2 additions and 4 deletions.
6 changes: 2 additions & 4 deletions models/lawnmower/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -572,7 +572,6 @@
</joint>
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>right_wheel_joint</joint_name>
<!--sub_topic>servo_0</sub_topic-->
<sub_topic>command/motor_speed</sub_topic>
<use_actuator_msg>true</use_actuator_msg>
<actuator_number>0</actuator_number>
Expand All @@ -589,7 +588,6 @@
</plugin>
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>left_wheel_joint</joint_name>
<!--sub_topic>servo_1</sub_topic-->
<sub_topic>command/motor_speed</sub_topic>
<use_actuator_msg>true</use_actuator_msg>
<actuator_number>1</actuator_number>
Expand All @@ -607,15 +605,15 @@
<!-- Note: SIM_GZ_SV_FAIL1 defines servo_0 etc. -->
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>cutter_blades_joint</joint_name>
<sub_topic>servo_2</sub_topic>
<sub_topic>servo_0</sub_topic>
<!-- p_gain>1.0</p_gain>
<cmd_max>2000.0</cmd_max>
<cmd_min>1000.0</cmd_min>
<cmd_offset>0.0</cmd_offset -->
</plugin>
<plugin filename="gz-sim-joint-controller-system" name="gz::sim::systems::JointController">
<joint_name>engine_visual_joint</joint_name>
<sub_topic>servo_3</sub_topic>
<sub_topic>servo_1</sub_topic>
<p_gain>10.0</p_gain>
<!-- use_actuator_msg>false</use_actuator_msg>
<initial_velocity>0</initial_velocity>
Expand Down

0 comments on commit 3691e12

Please sign in to comment.