Skip to content

Commit

Permalink
Merge pull request #17 from traclabs/bugfix/demos-25-mars-rover-rviz
Browse files Browse the repository at this point in the history
Updates to .xacro and .gazebo file to have the rover visible in Rviz
  • Loading branch information
EzraBrooks authored Apr 30, 2024
2 parents cd1eb01 + a010c9c commit 5a67b1c
Show file tree
Hide file tree
Showing 7 changed files with 61 additions and 44 deletions.
20 changes: 10 additions & 10 deletions models/curiosity_path/urdf/arm.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -113,15 +113,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_01_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_02_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_02_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -191,15 +191,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_03_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_03_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_03_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_03_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -270,15 +270,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_04_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_04_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_04_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_04_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -349,15 +349,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_tools_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_tools_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/arm_tools_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/arm_tools_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down
4 changes: 2 additions & 2 deletions models/curiosity_path/urdf/chassis.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -25,15 +25,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/chassis_full_fixed_glitch_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/chassis_full_fixed_glitch_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/chassis_full_fixed_glitch_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/chassis_full_fixed_glitch_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down
19 changes: 18 additions & 1 deletion models/curiosity_path/urdf/curiosity_mars_rover.gazebo
Original file line number Diff line number Diff line change
Expand Up @@ -50,21 +50,27 @@
<!-- Wheel Joints Interfaces-->
<joint name="front_wheel_L_joint">
<command_interface name="velocity" />
<state_interface name="position" />
</joint>
<joint name="middle_wheel_L_joint">
<command_interface name="velocity" />
<state_interface name="position" />
</joint>
<joint name="back_wheel_L_joint">
<command_interface name="velocity" />
<state_interface name="position" />
</joint>
<joint name="front_wheel_R_joint">
<command_interface name="velocity" />
<state_interface name="position" />
</joint>
<joint name="middle_wheel_R_joint">
<command_interface name="velocity" />
<state_interface name="position" />
</joint>
<joint name="back_wheel_R_joint">
<command_interface name="velocity" />
<state_interface name="position" />
</joint>
<!-- Steering Joints Interfaces-->
<joint name="suspension_steer_F_L_joint">
Expand Down Expand Up @@ -112,6 +118,17 @@
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>

<!-- Passive joints - No command interface -->
<joint name="suspension_arm_B2_L_joint">
<state_interface name="position"/>
</joint>

<joint name="suspension_arm_B2_R_joint">
<state_interface name="position"/>
</joint>


</ros2_control>

<gazebo>
Expand Down Expand Up @@ -301,4 +318,4 @@
<mu2>0.3</mu2>
</gazebo>

</robot>
</robot>
24 changes: 12 additions & 12 deletions models/curiosity_path/urdf/left_wheel_group.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/left_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/left_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/left_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/left_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -46,15 +46,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -95,15 +95,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -172,15 +172,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B2_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B2_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B2_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B2_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -250,15 +250,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_F_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -398,15 +398,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_B_L_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down
24 changes: 12 additions & 12 deletions models/curiosity_path/urdf/right_wheel_group.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/right_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/right_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/right_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/right_axis_jointfix_v2.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -44,15 +44,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -95,15 +95,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -172,15 +172,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B2_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B2_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_arm_B2_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_arm_B2_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -251,15 +251,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_F_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down Expand Up @@ -394,15 +394,15 @@
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</collision>

<visual>
<origin xyz="0 0 0"
rpy="0 0 0"/>
<geometry>
<mesh filename="$(find simulation)/models/curiosity_path/meshes/suspension_steer_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
<mesh filename="package://simulation/models/curiosity_path/meshes/suspension_steer_B_R_fixed.dae" scale="${scale_XYZ} ${scale_XYZ} ${scale_XYZ}"/>
</geometry>
</visual>

Expand Down
Loading

0 comments on commit 5a67b1c

Please sign in to comment.