ros-naoqi / pepper_robot

Meta-package for basic Pepper robot-related packages
25 stars 47 forks source link

adding sensors to Gazebo #23

Closed nlyubova closed 8 years ago

kochigami commented 8 years ago

Hi, I'd like to use sensor data on pepper gazebo, but I'm a newbie. I have one question and one small comment on adding 2D camera plugins on pepperGazebo.xacro. Before I found #23, I tried writing my own codes (I'll show it below). So I compared two codes.

Question about image size: I think the size of image topic (/pepper_robot/camera/front(bottom)/image_raw ) is width: 320 and height: 240, but pepper documentation says width: 640 and height: 480.

23 follows the documentation, but I'm not sure which (320x240 or 640x480) is right...

I found nao gazebo also uses 640x480 and there is no difference on image viewer though.

Small comment on bottom camera topic: I found the reason why the min value of focus range is set to 0.05 instead of 0.3 is avoiding showing split pepper's hands. I think it's helpful for following why 0.05 is set if there is some comments on the value.

The code is here:

<clip>
   <near>0.05</near>
   <far>500</far>
</clip>

my code (I set 0.3 based on the documentation) pepper_gazebo_bottom_camera_0 3_is_set

pull request 23 (0.05 is set) pepper_gazebo_bottom_camera_pull_request_23

My code is like this:

    <!-- Camera -->
    <gazebo reference="CameraTop_frame">
      <sensor type="camera" name="CameraTop">
        <update_rate>5.0</update_rate>
        <camera name="camera_top">
          <horizontal_fov>0.99832838</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
            <format>R8G8B8</format>
          </image>
          <clip>
            <near>0.3</near>
            <far>500</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
    <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
          <robotNamespace>pepper_robot</robotNamespace>
          <alwaysOn>true</alwaysOn>
          <updateRate>5.0</updateRate>
          <cameraName>camera/front/</cameraName>
          <imageTopicName>image_raw</imageTopicName>
          <cameraInfoTopicName>camera_info</cameraInfoTopicName>
          <frameName>CameraTop_optical_frame</frameName>
          <hackBaseline>0.07</hackBaseline>
          <distortionK1>0.092132</distortionK1>
          <distortionK2>-0.310808</distortionK2>
          <distortionK3>0.002515</distortionK3>
          <distortionT1>0.004544</distortionT1>
          <distortionT2>0.0</distortionT2>
        </plugin>
      </sensor>
    </gazebo>

    <gazebo reference="CameraBottom_frame">
      <sensor type="camera" name="CameraBottom">
        <update_rate>5.0</update_rate>
        <camera name="camera_bottom">
          <horizontal_fov>0.99832838</horizontal_fov>
          <image>
            <width>640</width>
            <height>480</height>
            <format>R8G8B8</format>
          </image>
          <clip>
            <near>0.3</near>
            <far>500</far>
          </clip>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise>
        </camera>
        <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
          <robotNamespace>pepper_robot</robotNamespace>
          <alwaysOn>true</alwaysOn>
          <updateRate>5.0</updateRate>
          <cameraName>camera/bottom/</cameraName>
          <imageTopicName>image_raw</imageTopicName>
          <cameraInfoTopicName>camera_info</cameraInfoTopicName>
          <frameName>CameraBottom_optical_frame</frameName>
          <hackBaseline>0.07</hackBaseline>
          <distortionK1>0.162668</distortionK1>
          <distortionK2>-0.315957</distortionK2>
          <distortionK3>0.019594</distortionK3>
          <distortionT1>-0.004876</distortionT1>
          <distortionT2>0.0</distortionT2>
        </plugin>
      </sensor>
    </gazebo>

In order to obtain distortionK1/ K2/ K3/ T1/ T2, I excuted

roslaunch pepper_bringup pepper_full.launch
rosrun camera_calibration cameracalibrator.py --size 6x4 --square 0.032 image:=/pepper_robot/camera/front(or bottom)/image_raw

(and this returns the image size as width: 320, height: 240)

k-okada commented 8 years ago

@kochigami I'm +1 for your proposal (320x240 and set near clip to 0.05), could you create new Pr for this?

nlyubova commented 8 years ago

@k-okada , I'll fix my PR, but why should we use 320x240 ?

nlyubova commented 8 years ago

@kochigami thank you for your work, let's see what should we update:

k-okada commented 8 years ago

I thought if the real robot publishes 320x240, we expect simulation is also publish same size.

◉ Kei Okada

On Mon, Sep 5, 2016 at 5:38 PM, Natalia Lyubova notifications@github.com wrote:

@k-okada https://github.com/k-okada , I'll fix my PR, but why should we use 320x240 ?

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/ros-naoqi/pepper_robot/pull/23#issuecomment-244690511, or mute the thread https://github.com/notifications/unsubscribe-auth/AAeG3JZ84EYrih149jnPCmgM8NtvPbGBks5qm9UUgaJpZM4JC5zw .

nlyubova commented 8 years ago

the real robot publishes the resolution that we ask it. In naoqi_driver, 320x240 is a default resolution but you can choose any resolution in the config file. 640x480 is the official maximum resolution, and both work well

nlyubova commented 8 years ago

regarding the distortion parameters, the one I've taken are from naoqi_driver, it is better to keep them like it is (to correspond to the one real robot publish)

nlyubova commented 8 years ago

Please, check the updated PR, and let's merge sensors because we need them as well

k-okada commented 8 years ago

@kochigami please check if this is ok for you.

kochigami commented 8 years ago

Sorry for just commenting with my bad English and thank you very much for your kind reply. This pull request is ok for merge!

I got the reason why the image size is 640x480. Thank you very much.