wip: removed unused files
This commit is contained in:
@@ -131,7 +131,7 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.2</mu>
|
<mu>1.2</mu>
|
||||||
<mu2>0</mu2>
|
<mu2>0</mu2>
|
||||||
<fdir1 gz:expressed_in="base">1 1 0</fdir1>
|
<fdir1 gz:expressed_in="base_link">1 1 0</fdir1>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
</surface>
|
</surface>
|
||||||
@@ -165,7 +165,7 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.2</mu>
|
<mu>1.2</mu>
|
||||||
<mu2>0</mu2>
|
<mu2>0</mu2>
|
||||||
<fdir1 gz:expressed_in="base">1 -1 0</fdir1>
|
<fdir1 gz:expressed_in="base_link">1 -1 0</fdir1>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
</surface>
|
</surface>
|
||||||
@@ -199,7 +199,7 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.2</mu>
|
<mu>1.2</mu>
|
||||||
<mu2>0</mu2>
|
<mu2>0</mu2>
|
||||||
<fdir1 gz:expressed_in="base">1 -1 0</fdir1>
|
<fdir1 gz:expressed_in="base_link">1 -1 0</fdir1>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
</surface>
|
</surface>
|
||||||
@@ -233,7 +233,7 @@
|
|||||||
<ode>
|
<ode>
|
||||||
<mu>1.2</mu>
|
<mu>1.2</mu>
|
||||||
<mu2>0</mu2>
|
<mu2>0</mu2>
|
||||||
<fdir1 gz:expressed_in="base">1 1 0</fdir1>
|
<fdir1 gz:expressed_in="base_link">1 1 0</fdir1>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
</surface>
|
</surface>
|
||||||
@@ -246,17 +246,25 @@
|
|||||||
<limit effort="100000" velocity="5"/>
|
<limit effort="100000" velocity="5"/>
|
||||||
<origin rpy="0 0 0" xyz="-0.11 0.11 0"/>
|
<origin rpy="0 0 0" xyz="-0.11 0.11 0"/>
|
||||||
</joint>
|
</joint>
|
||||||
<gazebo>
|
<ros2_control name="SherpaSystem" type="system">
|
||||||
<plugin filename="gz-sim-mecanum-drive-system" name="gz::sim::systems::MecanumDrive">
|
<hardware>
|
||||||
<front_left_joint>wheel_fl_joint</front_left_joint>
|
<plugin>ros2_control/GenericSystemInterface</plugin>
|
||||||
<front_right_joint>wheel_fr_joint</front_right_joint>
|
</hardware>
|
||||||
<back_left_joint>wheel_bl_joint</back_left_joint>
|
<joint name="wheel_fl_joint">
|
||||||
<back_right_joint>wheel_br_joint</back_right_joint>
|
<command_interface name="velocity"/>
|
||||||
<wheel_separation>0.22</wheel_separation>
|
<state_interface name="velocity"/>
|
||||||
<wheelbase>0.22</wheelbase>
|
</joint>
|
||||||
<wheel_radius>0.04</wheel_radius>
|
<joint name="wheel_fr_joint">
|
||||||
<min_acceleration>-5</min_acceleration>
|
<command_interface name="velocity"/>
|
||||||
<max_acceleration>5</max_acceleration>
|
<state_interface name="velocity"/>
|
||||||
</plugin>
|
</joint>
|
||||||
</gazebo>
|
<joint name="wheel_bl_joint">
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="wheel_br_joint">
|
||||||
|
<command_interface name="velocity"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
</joint>
|
||||||
|
</ros2_control>
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
Reference in New Issue
Block a user