ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The ZED creates its own base_link which I found to be problematic. Here is where it is created:
https://github.com/stereolabs/zed-ros-wrapper/blob/3c643fc9f75f1053db31931542fda7ac149a2ff3/zed_wrapper/urdf/zed_descr.urdf.xacro#L51
I added the frames from the ZED manually to my URDF and setting the publish_urdf argument to false for zed_camera.launch
https://github.com/bob-ROS/asc_project/blob/cc397c66f2c9a6b7bff4dc3b8e521d333297ec15/asc_description/urdf/asc.urdf_real.xacro#L205
You could probably resolve this by rewriting the existing zed URDF file to not use the base_link and then connect your existing base_link to e.g. "zed_base_link".
2 | No.2 Revision |
The ZED creates its own base_link which I found to be problematic. Here is where it is created:
https://github.com/stereolabs/zed-ros-wrapper/blob/3c643fc9f75f1053db31931542fda7ac149a2ff3/zed_wrapper/urdf/zed_descr.urdf.xacro#L51
I added the frames from the ZED manually to my URDF and setting the publish_urdf argument to false for zed_camera.launch
https://github.com/bob-ROS/asc_project/blob/cc397c66f2c9a6b7bff4dc3b8e521d333297ec15/asc_description/urdf/asc.urdf_real.xacro#L205
<link name="zed_camera_center">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://asc_description/meshes/ZED/ZED.stl"/>
</geometry>
<material name="light_grey">
<color rgba="0.8 0.8 0.8 0.8"/>
</material>
</visual> </link>
<joint name="base_to_camera" type="fixed">
<origin xyz="0.149 0 0.49" rpy="0 -0.1 0"/> <!-- tune pitch here -->
<parent link="base_link"/>
<child link="zed_camera_center"/> </joint> <link name="camera_link_pc"/> <joint name="camera_to_pc" type="fixed">
<origin xyz="0 0 0" rpy="-1.57 0 -1.57"/>
<parent link="zed_camera_center"/>
<child link="camera_link_pc"/> </joint>
<!-- Left Camera --> <joint name="zed_left_camera_joint" type="fixed">
<parent link="zed_camera_center"/>
<child link="zed_left_camera_frame"/>
<origin xyz="0 0.06 0" rpy="0 0 0"/> </joint> <link name="zed_left_camera_frame"/> <joint name="zed_left_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-1.57079632679 0.0
-1.57079632679"/>
<parent link="zed_left_camera_frame"/>
<child link="zed_left_camera_optical_frame"/> </joint> <link name="zed_left_camera_optical_frame"/> <!-- Right Camera --> <joint name="zed_right_camera_joint" type="fixed">
<parent link="zed_camera_center"/>
<child link="zed_right_camera_frame"/>
<origin xyz="0 -0.06 0" rpy="0 0 0"/> </joint> <link name="zed_right_camera_frame"/> <joint name="zed_right_camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-1.57079632679 0.0
-1.57079632679"/>
<parent link="zed_right_camera_frame"/>
<child link="zed_right_camera_optical_frame"/> </joint> <link name="zed_right_camera_optical_frame"/>
You could probably resolve this by rewriting the existing zed URDF file to not use the base_link and then connect your existing base_link to e.g. "zed_base_link".