Gazebo | Ignition | Community
Ask Your Question
0

Adding Intel Camera To Robot End-Effector

asked 2020-04-30 17:40:10 -0500

Iyantiram gravatar image

Hello All,

I am using ROS Melodic and Gazebo 9.13.

I am trying to visualise a 6 DOF robot (like the UR5) with the Intel Depthsense camera attached to the end-effector.

My problem: I can't seem to attach the camera to the wrist_3_link of the robot

Can you point out what is wrong with the way I am adding the camera to the robot's link?

What I tried:

the launch file:

<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />

<param name="robot_description" command="$(find xacro)/xacro '$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />

<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="spawn_ur5" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot -z 0.1" respawn="false" output="screen" />

<!-- Add the Intel realsense to the UR5 End Effector -->
<param name="realsense2_camera" command="$(find xacro)/xacro  '$(find camera)/urdf/ur5realsense.xacro' use_nominal_extrinsics:=true" />

<!-- push camera to gazebo -->
<node name="spawn_camera" pkg="gazebo_ros" type="spawn_model" args="-urdf -param realsense2_camera -model camera -x 1 -y 1 -z 0" respawn="false" output="screen" />

the wroking(?) xacro:

  <robot name="realsense2_camera" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />

  <link name="base_link" />
  <sensor_d435 parent="base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </sensor_d435>
  </robot>

the xacro that fails:

<?xml version="1.0"?>
<robot name="realsense2_camera" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />

  <link name="camera_link" />
  <sensor_d435 parent="camera_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </sensor_d435>

  <joint name="camerajoint" type="fixed">
    <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
    <parent link="wrist_3_link"/>
    <child link="camera_link"/>
    <axis xyz="0.0 0.0 0.0"/>
    <limit lower="0.0" upper="0.0" effort="0.0" velocity="0.0"/>
  </joint>

</robot>

links

Thank you.

Iyantiram

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2020-05-01 13:12:17 -0500

Iyantiram gravatar image

updated 2020-05-01 13:14:21 -0500

Thanks to nlamprian, I was able to fix these errors.

Just in case someone else is searching for how to attach just the camera (actual sensor is addressed in the link).

Here is the xacro (say test.xacro )that works for attaching the Intel D435 to the tool of UR5:

<robot name="robot_description" 
  xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:include filename="$(find ur5_description)/urdf/ur5_joint_limited_robot.urdf.xacro" />


  <!-- CAMERA -->

  <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro"/>
  <xacro:arg name="use_nominal_extrinsics" default="True" />

  <sensor_d435 parent="tool0">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </sensor_d435>

</robot>

Also what helped me was these steps:

xacro test.xacro > temp.urdf
check_urdf temp.urdf

That showed that I had inadvertently picked the wrong name for a link earlier.

Hope my mistakes help someone :)

Iyantiram

edit flag offensive delete link more

Comments

Do you have the full working example anywhere by any chance? If you make a public repo you will get much love from all over :)

silverhand gravatar imagesilverhand ( 2021-01-21 21:56:53 -0500 )edit

I am also wondering if you can provide any extra information on this, as I am trying to do something very similar with a Kuka Youbot?

sevenPillars gravatar imagesevenPillars ( 2021-05-12 10:08:06 -0500 )edit
0

answered 2020-05-01 00:24:55 -0500

You are only creating the camera links with the sensor_d435 macro, not the sensor itself. To add a camera sensor, you need this.

Here is how the urdf would look like:

<robot name="realsense2_camera" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />

  <sensor_d435 parent="wrist_3_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </sensor_d435>

  <gazebo reference="camera_link">
    <sensor name="camera" type="camera">
      ...
    </sensor>
  </gazebo>
</robot>
edit flag offensive delete link more

Comments

nlamprian,

Thank you for the comment.

I will follow up on what you said.

However, I am confused why the xacro I labeled working actually renders the camera without the additional "gazebo" tags.

Iyantiram gravatar imageIyantiram ( 2020-05-01 11:07:22 -0500 )edit

You urdf is broken. There are two camera_link links, one created by you and one by the macro. Secondly, in the working urdf, you see the camera, but that doesn't mean there is an actual sensor attached to it. Lastly, the camera urdf will have to be part of the arm urdf, and in the launch file, you will only spawn the arm model. Otherwise, you have two independent models, i.e. the camera is not attached to the arm.

nlamprian gravatar imagenlamprian ( 2020-05-01 12:24:36 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-04-30 17:37:22 -0500

Seen: 2,476 times

Last updated: May 01 '20