marcoesposito1988 / easy_handeye_demo

Virtual demonstration of a hand-eye calibration with easy_handeye, no hardware required
GNU General Public License v3.0
61 stars 22 forks source link

Realsense hand to base #10

Open lalazari opened 3 years ago

lalazari commented 3 years ago

Hello and thanks for your code. I am a beginner in ros and I am trying hand to base calibration using the panda robot and a realsense camera module. Based on the demo provided by you and a realsense launch file I created the following launch file:

`

<arg name="start_simulator" default="true" doc="Start a simulated tracking system with a trivial noise model" />
<arg name="eye_on_hand" default="false" />

<arg name="robot_ip" doc="The IP address of the UR5 robot" />

<arg name="marker_size" default="0.13" doc="Size of the ArUco marker used, in meters" />
<arg name="marker_id" default="582" doc="The ID of the ArUco marker used" />

<arg name="tracking_base_frame" value="camera_link" />
<arg name="tracking_marker_frame" value="camera_marker" />

<!-- these parameters depend on the robot; you can copy these for the Franka Panda -->
<arg name="move_group" value="panda_arm" />
<arg name="move_group_namespace" value="/" />
<arg name="robot_base_frame" value="panda_link0" />
<arg name="robot_effector_frame" value="panda_link7" />

<!-- start the robot (and an extra Rviz instance, sadly) -->
<include file="$(find moveit_resources_panda_moveit_config)/launch/demo.launch" />

<!-- start ArUco -->
<node name="aruco_tracker" pkg="aruco_ros" type="single">
    <remap from="/camera_info" to="/camera/color/camera_info" />
    <remap from="/image" to="/camera/color/image_raw" />
    <param name="image_is_rectified" value="true"/>
    <param name="marker_size"        value="$(arg marker_size)"/>
    <param name="marker_id"          value="$(arg marker_id)"/>

    <!--param name="reference_frame"    value="camera_color_frame"/>
    <param name="camera_frame"       value="camera_color_frame"/-->

    <param name="reference_frame"    value="camera_link"/>
    <param name="camera_frame"       value="camera_color_frame"/>

    <param name="marker_frame"       value="camera_marker" />
</node>

<!-- start easy_handeye -->
    <!-- start easy_handeye calibration procedure -->
<include file="$(find easy_handeye)/launch/calibrate.launch" >
    <arg name="start_rviz" value="false" />
    <arg name="publish_dummy" value="false" /> <!-- in our case it is done by the tracking simulator -->

    <arg name="move_group" value="$(arg move_group)" />
    <arg name="move_group_namespace" value="$(arg move_group_namespace)" />

    <arg name="eye_on_hand" value="$(arg eye_on_hand)" />
    <arg name="tracking_base_frame" value="$(arg tracking_base_frame)" />
    <arg name="tracking_marker_frame" value="$(arg tracking_marker_frame)" />
    <arg name="robot_base_frame" value="$(arg robot_base_frame)" />
    <arg name="robot_effector_frame" value="$(arg robot_effector_frame)" />

    <arg name="freehand_robot_movement" value="false" />
    <arg name="robot_velocity_scaling" value="0.5" />
    <arg name="robot_acceleration_scaling" value="0.2" />
</include>

<!-- start rviz with custom configuration -->
<node name="$(anon rviz)" pkg="rviz" type="rviz" respawn="true"
      args="-d $(find easy_handeye_demo)/launch/franka_panda/panda_config.rviz" output="screen" />

`

My problem is that when I open RVIZ the camera_link is located in the base of the robot and not in the proper position of the camera. How can I overcome this issue and calibrate my system?

Here is an rviz screenshot: camera_link

My tf tree having as Fixed Frame the camera_link: tf

Thank you

marcoesposito1988 commented 3 years ago

Hi @lalazari,

for the calibration process, you can ignore the position of the camera. It will be known only after calibrating, so it's a chicken-and-egg problem. What the easy_handeye launch files do is to publish an arbitrary transformation between the robot (base or hand) and the camera, so that the tf frame is at least visible in RViz, and you can figure out if the tracking is working.

Your launch file should allow you to calibrate, but I wouldn't recommend using the launch file from the demo as an example. There is a lot of customization for making the demo work at all. I would rather advise you to start from one of the launch files at https://github.com/IFL-CAMP/easy_handeye/tree/master/docs/example_launch