Skip to content

Commit

Permalink
Removing sr_hardware_control_loop.launch dependency on ur_description…
Browse files Browse the repository at this point in the history
… when arm:=false
  • Loading branch information
ethanfowler committed Aug 14, 2020
1 parent 5389aba commit 6a06b9e
Showing 1 changed file with 5 additions and 4 deletions.
9 changes: 5 additions & 4 deletions sr_robot_launch/launch/sr_hardware_control_loop.launch
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,9 @@
<!-- Set to true to spawn the position controllers for the arm-->
<arg name="arm_position" default="$(eval not arm_trajectory)"/>
<arg name="arm_speed_scale" default="0.5"/>
<arg name="kinematics_config" if="$(eval not arg('robot_model') == 'ur10e')" default="$(find ur_description)/config/ur10_default.yaml"/>
<arg name="kinematics_config" if="$(eval arg('robot_model') == 'ur10e')" default="$(find ur_e_description)/config/ur10e_default.yaml"/>
<arg name="kinematics_config" if="$(eval arg('arm') and not arg('robot_model') == 'ur10e')" default="$(find ur_description)/config/ur10_default.yaml"/>
<arg name="kinematics_config" if="$(eval arg('arm') and arg('robot_model') == 'ur10e')" default="$(find ur_e_description)/config/ur10e_default.yaml"/>
<arg name="kinematics_config" unless="$(arg arm)" default=""/>
<arg name="urcap_program_name" default="external_ctrl.urp"/>
<arg name="load_robot_description_command" default="xacro $(arg robot_description) prefix:=$(arg hand_id)_ initial_z:=$(arg initial_z) kinematics_config:=$(arg kinematics_config)"/>

Expand All @@ -66,7 +67,7 @@
</group>

<!-- So that the driver can check we're loading the right calibration -->
<rosparam command="load" file="$(arg kinematics_config)" ns="$(arg arm_prefix)_sr_ur_robot_hw"/>
<rosparam if="$(arg arm)" command="load" file="$(arg kinematics_config)" ns="$(arg arm_prefix)_sr_ur_robot_hw"/>

<include file="$(find sr_robot_launch)/launch/unimanual_controller_stopper.launch">
<arg name="side" value="$(arg side)"/>
Expand Down Expand Up @@ -134,7 +135,7 @@
</rosparam>

<!-- These will be loaded if hand is false so UR10 with box will load instead. -->
<group unless="$(arg hand)">
<group if="$(eval arg('arm') and not arg('hand'))">
<include file="$(find ros_ethercat_model)/launch/joint_state_publisher.launch">
<arg name="publish_rate" value="$(arg joint_state_pub_frequency)"/>
</include>
Expand Down

0 comments on commit 6a06b9e

Please sign in to comment.