Skip to content

Commit

Permalink
Add joints prefix param to all joints
Browse files Browse the repository at this point in the history
  • Loading branch information
jasiex01 committed Oct 18, 2023
1 parent 45b1dd5 commit 58cf2c5
Showing 1 changed file with 13 additions and 16 deletions.
29 changes: 13 additions & 16 deletions leo_description/urdf/macros.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
rockers_fixed:=true
footprint_link:=true
link_prefix:=''
joint_prefix:=''
joint_prefix:=''
imu_translation:='0.0628 -0.0314 -0.0393'">

<xacro:macro name="rocker_link" params="name">
Expand Down Expand Up @@ -131,7 +131,7 @@
<!-- JOINTS -->

<xacro:if value="${footprint_link}">
<joint name="base_joint" type="fixed">
<joint name="${joint_prefix}base_joint" type="fixed">
<origin xyz="0 0 0.19783" rpy="0 0 0"/>
<parent link="${link_prefix}base_footprint"/>
<child link="${link_prefix}base_link"/>
Expand All @@ -145,7 +145,7 @@
<xacro:property name="rockers_joint_type" value="revolute"/>
</xacro:unless>

<joint name="rocker_L_joint" type="${rockers_joint_type}">
<joint name="${joint_prefix}rocker_L_joint" type="${rockers_joint_type}">
<origin xyz="0.00263 0.14167 -0.04731" rpy="0 0 ${pi}"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}rocker_L_link"/>
Expand All @@ -154,7 +154,7 @@
<dynamics friction="1.0" damping="0.1"/>
</joint>

<joint name="rocker_R_joint" type="${rockers_joint_type}">
<joint name="${joint_prefix}rocker_R_joint" type="${rockers_joint_type}">
<origin xyz="0.00263 -0.14167 -0.04731" rpy="0 0 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}rocker_R_link"/>
Expand All @@ -164,7 +164,7 @@
<mimic joint="rocker_L_joint"/>
</joint>

<joint name="wheel_FL_joint" type="continuous">
<joint name="${joint_prefix}wheel_FL_joint" type="continuous">
<origin xyz="-0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_L_link"/>
<child link="${link_prefix}wheel_FL_link"/>
Expand All @@ -173,7 +173,7 @@
<dynamics friction="0.3125" damping="0.1"/>
</joint>

<joint name="wheel_RL_joint" type="continuous">
<joint name="${joint_prefix}wheel_RL_joint" type="continuous">
<origin xyz="0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_L_link"/>
<child link="${link_prefix}wheel_RL_link"/>
Expand All @@ -182,7 +182,7 @@
<dynamics friction="0.3125" damping="0.1"/>
</joint>

<joint name="wheel_FR_joint" type="continuous">
<joint name="${joint_prefix}wheel_FR_joint" type="continuous">
<origin xyz="0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_R_link"/>
<child link="${link_prefix}wheel_FR_link"/>
Expand All @@ -191,7 +191,7 @@
<dynamics friction="0.3125" damping="0.1"/>
</joint>

<joint name="wheel_RR_joint" type="continuous">
<joint name="${joint_prefix}wheel_RR_joint" type="continuous">
<origin xyz="-0.15256 -0.08214 -0.08802" rpy="0 0 0"/>
<parent link="${link_prefix}rocker_R_link"/>
<child link="${link_prefix}wheel_RR_link"/>
Expand All @@ -201,26 +201,26 @@
</joint>

<xacro:if value="${default_antenna}">
<joint name="antenna_joint" type="fixed">
<joint name="${joint_prefix}antenna_joint" type="fixed">
<origin xyz="-0.0052 0.056 -0.0065" rpy="0 0 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}antenna_link"/>
</joint>
</xacro:if>

<joint name="camera_joint" type="fixed">
<joint name="${joint_prefix}camera_joint" type="fixed">
<origin xyz="0.0971 0 -0.0427" rpy="0 0.2094 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}camera_frame"/>
</joint>

<joint name="camera_optical_joint" type="fixed">
<joint name="${joint_prefix}camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-${pi/2} 0.0 -${pi/2}"/>
<parent link="${link_prefix}camera_frame"/>
<child link="${link_prefix}camera_optical_frame"/>
</joint>

<joint name="imu_joint" type="fixed">
<joint name="${joint_prefix}imu_joint" type="fixed">
<origin xyz="${imu_translation}" rpy="0 0 0"/>
<parent link="${link_prefix}base_link"/>
<child link="${link_prefix}imu_frame"/>
Expand All @@ -231,8 +231,7 @@
<!-- LEO GAZEBO -->

<xacro:macro name="leo_gazebo"
params="robot_ns:=''
joint_prefix:=''">
params="robot_ns:='''">

<xacro:property name="link_prefix" value=""/>
<xacro:if value="${robot_ns != '' and robot_ns != '/'}">
Expand Down Expand Up @@ -485,10 +484,8 @@
robot_ns:=''">

<xacro:property name="link_prefix" value=""/>
<xacro:property name="joint_prefix" value=""/>
<xacro:if value="${robot_ns != '' and robot_ns != '/'}">
<xacro:property name="link_prefix" value="${robot_ns}/"/>
<xacro:property name="joint_prefix" value="${robot_ns}/"/>
</xacro:if>

<xacro:leo default_antenna="${default_antenna}"
Expand Down

0 comments on commit 58cf2c5

Please sign in to comment.