Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create Zed Camera Macro, use mounting hole as the camera base-link #771

Merged
merged 2 commits into from
Nov 24, 2021

Conversation

civerachb-cpr
Copy link
Contributor

This PR duplicates much of the work already done in #534, which appears to be stalled because of unresolved merge conflicts (?). If 534 gets merged feel free to close this PR without merging, but one (or both) PRs would greatly improve the usability of the Zed ROS wrapper.

The most notable difference with this PR is that I've added an additional link to the Zed model, corresponding to the mounting hole in the center-bottom of the camera. This link is now treated as the base-link for the whole camera, rather than the camera_center link. My reasoning here is that anyone attaching the camera to an existing robot is likely going to do so using that mounting hole, and using that link as the base for the camera allows the Zed to be attached flush with a mounting point already defined in the URDF (e.g. https://github.com/clearpathrobotics/lockmount_description).

For example, the following can be added to the URDF_EXTRAS parameter of a Clearpath Jackal to add a Zed camera to the robot:

<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">

  <xacro:include filename="$(find lockmount_description)/urdf/lockmount.urdf.xacro" />
  <xacro:lockmount parent_link="front_mount" prefix="front_zed" angle="-0.1">
    <origin xyz="0 0 0" rpy="0 0 0" />
  </xacro:lockmount>

  <xacro:include filename="$(find zed_wrapper)/urdf/zed_macro.urdf.xacro" />
  <xacro:zed_camera parent="front_zed_mount" model="zed2">
    <origin xyz="0 0 0" rpy="0 0 0" />
  </xacro:zed_camera>
</robot>

Resulting in this model:
zed_macro_example

…sting URDF. Make the base-link connect to the mounting hole of the camera instead of the camera's center (makes attaching the camera to a mounting point on another URDF easier).
@civerachb-cpr
Copy link
Contributor Author

Any chance for a review on this PR, please?

@garyedwards
Copy link

@civerachb-cpr I really support this change as it will make the urdf provided by this package much more usable. Also the base link at the mounting point makes a lot of sense.

Regarding the mounting point I have noticed the mesh provided by this package and the step file are different (mounting hole angle to base of camera) and that the body of the camera tapers slightly towards the lenses in section.

As such it seems that if the camera is mounted flush to the body it will be slightly pointing down. Maybe someone from @stereolabs (@Myzhar?) can comment. This seems like a bit of a design flaw but if true should be represented in the rpy between the base_link and camera_center

step file:

image

ros mesh:

image

@Myzhar
Copy link
Member

Myzhar commented Nov 22, 2021

@garyedwards we are evaluating how to better merge this PR to keep the repository as general as possible.
Furthermore, you are right, the ZED and the ZED2 cameras have a slope of 3° at the bottom, so this must be taken into consideration if adding the camera base link. [ZED Mini and ZED2i are not affected by this]

@garyedwards
Copy link

garyedwards commented Nov 22, 2021

Thanks for the reply @Myzhar. I assume the mounting hole is normal to the bottom surface as per the step file.

How is the centre point then calculated? Is it the centre point of the outer most circle making up the mounting hole and then directly up to intersect with a XY plane through the centre of both lenses? Is their any documentation showing this clearly?

@Myzhar
Copy link
Member

Myzhar commented Nov 22, 2021

How is the centre point then calculated? Is it the centre point of the outer most circle making up the mounting hole and then directly up to intersect with a XY plane through the centre of both lenses? Is their any documentation showing this clearly?

This has not yet been decided and is part of this union request.

@Myzhar Myzhar self-assigned this Nov 24, 2021
@Myzhar Myzhar self-requested a review November 24, 2021 08:40
@Myzhar
Copy link
Member

Myzhar commented Nov 24, 2021

@civerachb-cpr I'm finally testing the PR, but I have a problem.
I tried executing roslaunch zed_wrapper zed2.launch

and I get this error that I cannot solve:

$ roslaunch zed_wrapper zed2.launch 
... logging to /home/walter/.ros/log/532f1136-4b75-11ec-9042-2f2984f90461/roslaunch-walter-desktop-180776.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

name 'camera_name' is not defined 
when evaluating expression 'camera_name'
when instantiating macro: zed_camera (/home/walter/devel/ros1_ws/src/zed-ros-wrapper/zed_wrapper/urdf/zed_macro.urdf.xacro)
in file: /home/walter/devel/ros1_ws/src/zed-ros-wrapper/zed_wrapper/urdf/zed_descr.urdf.xacro
RLException: while processing /home/walter/devel/ros1_ws/src/zed-ros-wrapper/zed_wrapper/launch/include/zed_camera.launch.xml:
Invalid <param> tag: Cannot load command parameter [zed2_description]: command [['/opt/ros/noetic/lib/xacro/xacro', '/home/walter/devel/ros1_ws/src/zed-ros-wrapper/zed_wrapper/urdf/zed_descr.urdf.xacro', 'camera_name:=zed2', 'camera_model:=zed2', 'base_frame:=base_link', 'cam_pos_x:=0.0', 'cam_pos_y:=0.0', 'cam_pos_z:=0.0', 'cam_roll:=0.0', 'cam_pitch:=0.0', 'cam_yaw:=0.0']] returned with code [2]. 

Param xml is <param name="$(arg camera_name)_description" command="$(find xacro)/xacro '$(find zed_wrapper)/urdf/zed_descr.urdf.xacro'                         camera_name:=$(arg camera_name)                         camera_model:=$(arg camera_model)                         base_frame:=$(arg base_frame)                         cam_pos_x:=$(arg cam_pos_x)                         cam_pos_y:=$(arg cam_pos_y)                         cam_pos_z:=$(arg cam_pos_z)                         cam_roll:=$(arg cam_roll)                         cam_pitch:=$(arg cam_pitch)                         cam_yaw:=$(arg cam_yaw)"/>
The traceback for the exception was written to the log file

@Myzhar
Copy link
Member

Myzhar commented Nov 24, 2021

I tried also by calling xacro directly outside the launch file, but the error is the same:

$ xacro zed_descr.urdf.xacro camera_name:=zed2 
name 'camera_name' is not defined 
when evaluating expression 'camera_name'
when instantiating macro: zed_camera (/home/walter/devel/ros1_ws/src/zed-ros-wrapper/zed_wrapper/urdf/zed_macro.urdf.xacro)
in file: zed_descr.urdf.xacro

@Myzhar
Copy link
Member

Myzhar commented Nov 24, 2021

@civerachb-cpr there were syntax errors in your version of zed_descr.urdf.xacro,
e.g. ${camera_name} -> $(arg camera_name)
I fixed them and now everything works as expected.

I'm adding the modifications proposed by @garyedwards (base slope for ZED and ZED2, correct position of the optical frame) and I'm going to merge the PR

@Myzhar Myzhar mentioned this pull request Nov 24, 2021
@Myzhar Myzhar merged commit 186d662 into stereolabs:master Nov 24, 2021
Myzhar added a commit to stereolabs/zed-ros2-wrapper that referenced this pull request Dec 1, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Development

Successfully merging this pull request may close these issues.

3 participants