Browse Source

URDF bug fixed working on H1

Merge branch 'bugfix/required_realsense_xacro_arg'
pull/8/head
Aaron Edsinger 4 years ago
parent
commit
8df4a597e9
3 changed files with 3 additions and 1 deletions
  1. +1
    -1
      stretch_calibration/nodes/collect_head_calibration_data
  2. +1
    -0
      stretch_core/launch/d435i_basic.launch
  3. +1
    -0
      stretch_description/urdf/stretch_d435i.xacro

+ 1
- 1
stretch_calibration/nodes/collect_head_calibration_data View File

@ -207,7 +207,7 @@ class CollectHeadCalibrationDataNode:
if timeout:
rospy.logerr('collect_head_calibration_data get_samples: timeout while waiting for sample.')
#raise IOError('Timeout')
raise Exception('Timed out waiting for joint_states/accelerations/markers messages after 10 seconds')
with self.data_lock:
#set backlash joint state

+ 1
- 0
stretch_core/launch/d435i_basic.launch View File

@ -17,6 +17,7 @@
<arg name="depth_fps" value="15"/>
<arg name="enable_infra1" value="false"/>
<arg name="enable_infra2" value="false"/>
<arg name="enable_accel" value="true"/>
<arg name="depth_width" value="$(arg depth_width)"/>
<arg name="depth_height" value="$(arg depth_height)"/>

+ 1
- 0
stretch_description/urdf/stretch_d435i.xacro View File

@ -2,6 +2,7 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="stretch_d435i">
<xacro:arg name="use_nominal_extrinsics" default="true"/>
<xacro:arg name="add_plug" default="false"/>
<xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro"/>
<!-- xyz = "

Loading…
Cancel
Save