Skip to content

Commit 7701349

Browse files
authored
Fix: Ewellix Parameters (#278)
Add plate and mount parameters to URDF
1 parent 2e9e2df commit 7701349

File tree

1 file changed

+8
-2
lines changed

1 file changed

+8
-2
lines changed

clearpath_manipulators_description/urdf/lift/ewellix.urdf.xacro

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,8 @@
1111
parent_link
1212
*origin
1313
ewellix_type:=tlt_x25
14-
add_plate:=True
14+
add_plate:=''
15+
add_mount:=''
1516
parameters_file:=''
1617
initial_positions:=''
1718
initial_positions_file:=''
@@ -39,6 +40,8 @@
3940
<xacro:property name="_sim_gazebo" value="$(arg is_sim)" />
4041

4142
<!-- Default Hardware Parameters -->
43+
<xacro:property name="_add_plate" value="True"/>
44+
<xacro:property name="_add_mount" value="True"/>
4245
<xacro:property name="_port" value="/dev/ttyUSB0"/>
4346
<xacro:property name="_baud" value="38400"/>
4447
<xacro:property name="_timeout" value="1000"/>
@@ -54,6 +57,8 @@
5457
<xacro:if value="${generate_ros2_control_tag != ''}"> <xacro:property name="_generate_ros2_control_tag" value="${generate_ros2_control_tag}" lazy_eval="false"/> </xacro:if>
5558
<xacro:if value="${use_fake_hardware != ''}"> <xacro:property name="_use_fake_hardware" value="${use_fake_hardware}" lazy_eval="false"/> </xacro:if>
5659
<xacro:if value="${sim_gazebo != ''}"> <xacro:property name="_sim_gazebo" value="${sim_gazebo}" lazy_eval="false"/> </xacro:if>
60+
<xacro:if value="${add_plate != ''}"> <xacro:property name="_add_plate" value="${add_plate}" lazy_eval="false"/> </xacro:if>
61+
<xacro:if value="${add_mount != ''}"> <xacro:property name="_add_mount" value="${add_mount}" lazy_eval="false"/> </xacro:if>
5762
<xacro:if value="${port != ''}"> <xacro:property name="_port" value="${port}" lazy_eval="false"/> </xacro:if>
5863
<xacro:if value="${baud != ''}"> <xacro:property name="_baud" value="${baud}" lazy_eval="false"/> </xacro:if>
5964
<xacro:if value="${timeout != ''}"> <xacro:property name="_timeout" value="${timeout}" lazy_eval="false"/> </xacro:if>
@@ -65,7 +70,8 @@
6570
<xacro:ewellix_lift
6671
parent="${parent_link}"
6772
tf_prefix="${_tf_prefix}"
68-
add_plate="${add_plate}"
73+
add_plate="${_add_plate}"
74+
add_mount="${_add_mount}"
6975
initial_positions="${_initial_positions}"
7076
parameters_file="${_parameters_file}"
7177
generate_ros2_control_tag="${_generate_ros2_control_tag}"

0 commit comments

Comments
 (0)