Skip to content

Commit

Permalink
Updated mp_500 and mp_400 urdf
Browse files Browse the repository at this point in the history
  • Loading branch information
AdarshKaran committed Nov 28, 2024
1 parent fa7fdf8 commit ab679b2
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 20 deletions.
18 changes: 9 additions & 9 deletions robots/mp_400/urdf/mp_400_body.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,6 @@

<link name="base_footprint"/>

<joint name="base_footprint_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 -1"/>
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
<joint_properties damping="1" friction="1"/>
<parent link="base_footprint"/>
<child link="base_link"/>
</joint>

<link name="base_link">
<inertial>
<mass value="30"/>
Expand All @@ -32,6 +23,15 @@
</collision>
</link>

<joint name="base_footprint_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 -1"/>
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
<joint_properties damping="1" friction="1"/>
<parent link="base_link"/>
<child link="base_footprint"/>
</joint>

<!-- Sensors -->
<joint name="lidar_1_joint" type="fixed">
<axis xyz="0 1 0"/>
Expand Down
2 changes: 1 addition & 1 deletion robots/mp_400/urdf/mp_400_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
command_topic="cmd_vel"
odometry_topic="odom"
odom_frame="odom"
base_frame="base_footprint"
base_frame="base_link"
max_wheel_torque="1000"
max_acceleration="20.0"
/>
Expand Down
18 changes: 9 additions & 9 deletions robots/mp_500/urdf/mp_500_body.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,6 @@

<link name="base_footprint"/>

<joint name="base_footprint_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 -1"/>
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
<joint_properties damping="1" friction="1"/>
<parent link="base_footprint"/>
<child link="base_link"/>
</joint>

<link name="base_link">
<inertial>
<mass value="5"/>
Expand All @@ -32,6 +23,15 @@
</collision>
</link>

<joint name="base_footprint_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 0 -1"/>
<!-- <limit effort="1000.0" lower="-1e+16" upper="1e+16" velocity="3.5"/> -->
<joint_properties damping="1" friction="1"/>
<parent link="base_link"/>
<child link="base_footprint"/>
</joint>

<joint name="caster_wheel_joint" type="fixed">
<origin rpy="-1.570796 0 1.570796 " xyz="-0.43 0. 0.176"/>
<axis xyz="0 -1 0"/>
Expand Down
2 changes: 1 addition & 1 deletion robots/mp_500/urdf/mp_500_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
command_topic="cmd_vel"
odometry_topic="odom"
odom_frame="odom"
base_frame="base_footprint"
base_frame="base_link"
max_wheel_torque="200"
max_acceleration="1.0"
/>
Expand Down

0 comments on commit ab679b2

Please sign in to comment.