gazebosim / gazebo-classic

Gazebo classic. For the latest version, see https://github.com/gazebosim/gz-sim
http://classic.gazebosim.org/
Other
1.2k stars 482 forks source link

Very low Real Time Factor when using wideanglecamera #3359

Closed Juhyung-L closed 11 months ago

Juhyung-L commented 1 year ago

OS: Ubuntu 22.04 Gazebo Version: 11

I have 3 cameras attached to a box (right, left, and back sides of the box).

When the camera type is type="camera", the real time factor is around 0.6-0.7 When I change the type to type="wideanglecamera", the real time factor drops to ~0.1

I get that wideanglecamera captures a wider view and is more computationally expensive to simulate, but even when I set the FOV of the wideanglecamera to be the same as camera,(I set it to 90degrees/1.5708radians) the RTF is still ~0.1.

urdf for wideanglecamera

<?xml version="1.0"?>
<robot name="camera_test" xmlns:xacro="http://ros.org/wiki/xacro">
    <!-- define robot constants -->
    <xacro:property name="base_width" value="2"/>
    <xacro:property name="base_height" value="2"/>
    <xacro:property name="base_depth" value="2"/>

    <xacro:property name="camera_size" value="0.1"/>
    <xacro:property name="camera_zoff" value="0.3"/>

    <!-- define intertial property macros -->
    <xacro:macro name="box_inertia" params="m w h d">
        <inertial>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <mass value="${m}"/>
            <inertia ixx="${(m/12) * (h*h + d*d)}" ixy="0.0" ixz="0.0" iyy="${(m/12) * (w*w + d*d)}" iyz="0.0" izz="${(m/12) * (w*w + h*h)}"/>
        </inertial>
    </xacro:macro>

    <!-- wheelchair base -->
    <link name="base_link">
        <origin rpy="0 0 0 " xyz="0 0 0"/>
        <visual>
            <geometry>
                <box size="${base_width} ${base_height} ${base_depth}"/>
            </geometry>
            <material name="Cyan">
                <color rgba="0 1.0 1.0 1.0"/>
            </material>
        </visual>
        <collision>
            <geometry>
                <box size="${base_width} ${base_height} ${base_depth}"/>
            </geometry>
        </collision>
        <xacro:box_inertia m="10" w="${base_width}" h="${base_height}" d="${base_depth}"/>
    </link>

    <!-- cameras -->
    <xacro:macro name="camera_link" params="prefix x_reflect y_reflect angle_number">
        <link name="camera_${prefix}_link">
            <visual>
                <geometry>
                    <box size="${camera_size} ${camera_size} ${camera_size}"/>
                </geometry>
                <material name="Red">
                    <color rgba="1.0 0.0 0.0 1.0"/>
                </material>
            </visual>
            <collision>
                <geometry>
                    <box size="${camera_size} ${camera_size} ${camera_size}"/>
                </geometry>
            </collision>
            <xacro:box_inertia m="1" w="${camera_size}" h="${camera_size}" d="${camera_size}"/>
        </link>

        <joint name="camera_${prefix}_joint" type="fixed">
            <parent link="base_link"/>
            <child link="camera_${prefix}_link"/>
            <origin xyz="${x_reflect*base_width/2} ${y_reflect*base_height/2} ${camera_zoff}" rpy="0 0 ${angle_number*pi/2}"/>
        </joint> 
    </xacro:macro>

    <!-- xacro:camera_link prefix="front" x_reflect="1.0" y_reflect="0.0" angle_number="0"/-->
    <xacro:camera_link prefix="left" x_reflect="0.0" y_reflect="1.0" angle_number="1"/>
    <xacro:camera_link prefix="back" x_reflect="-1.0" y_reflect="0.0" angle_number="2"/>
    <xacro:camera_link prefix="right" x_reflect="0.0" y_reflect="-1.0" angle_number="3"/>

    <gazebo reference="camera_left_link">
        <sensor name="camera_left" type="wideanglecamera">
            <camera>
                <horizontal_fov>1.5708</horizontal_fov>
                <image>
                    <width>320</width>
                    <height>320</height>
                    <format>R8G8B8</format>
                </image>
                <clip>
                    <near>0.02</near>
                    <far>100</far>
                </clip>
                <lens>
                    <type>stereographic</type>
                    <scale_to_hfov>true</scale_to_hfov>
                    <cutoff_angle>1.5708</cutoff_angle>
                    <env_texture_size>512</env_texture_size>
                </lens>
            </camera>
            <always_on>1</always_on>
            <update_rate>30</update_rate>
        </sensor>
    </gazebo>

    <gazebo reference="camera_back_link">
        <sensor name="camera_back" type="wideanglecamera">
            <camera>
                <horizontal_fov>1.5708</horizontal_fov>
                <image>
                    <width>320</width>
                    <height>320</height>
                    <format>R8G8B8</format>
                </image>
                <clip>
                    <near>0.02</near>
                    <far>100</far>
                </clip>
                <lens>
                    <type>stereographic</type>
                    <scale_to_hfov>true</scale_to_hfov>
                    <cutoff_angle>1.5708</cutoff_angle>
                    <env_texture_size>512</env_texture_size>
                </lens>
            </camera>
            <always_on>1</always_on>
            <update_rate>30</update_rate>
        </sensor>
    </gazebo>

    <gazebo reference="camera_right_link">
        <sensor name="camera_right" type="wideanglecamera">
            <camera>
                <horizontal_fov>1.5708</horizontal_fov>
                <image>
                    <width>320</width>
                    <height>320</height>
                    <format>R8G8B8</format>
                </image>
                <clip>
                    <near>0.02</near>
                    <far>100</far>
                </clip>
                <lens>
                    <type>stereographic</type>
                    <scale_to_hfov>true</scale_to_hfov>
                    <cutoff_angle>1.5708</cutoff_angle>
                    <env_texture_size>512</env_texture_size>
                </lens>
            </camera>
            <always_on>1</always_on>
            <update_rate>30</update_rate>
        </sensor>
    </gazebo>

</robot>

urdf for camera

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from camera_test.xacro              | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="camera_test">
  <!-- wheelchair base -->
  <link name="base_link">
    <origin rpy="0 0 0 " xyz="0 0 0"/>
    <visual>
      <geometry>
        <box size="2 2 2"/>
      </geometry>
      <material name="Cyan">
        <color rgba="0 1.0 1.0 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <box size="2 2 2"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="10"/>
      <inertia ixx="6.666666666666667" ixy="0.0" ixz="0.0" iyy="6.666666666666667" iyz="0.0" izz="6.666666666666667"/>
    </inertial>
  </link>
  <link name="camera_left_link">
    <visual>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
      <material name="Red">
        <color rgba="1.0 0.0 0.0 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="0.001666666666666667" ixy="0.0" ixz="0.0" iyy="0.001666666666666667" iyz="0.0" izz="0.001666666666666667"/>
    </inertial>
  </link>
  <joint name="camera_left_joint" type="fixed">
    <parent link="base_link"/>
    <child link="camera_left_link"/>
    <origin rpy="0 0 1.5707963267948966" xyz="0.0 1.0 0.3"/>
  </joint>
  <link name="camera_back_link">
    <visual>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
      <material name="Red">
        <color rgba="1.0 0.0 0.0 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="0.001666666666666667" ixy="0.0" ixz="0.0" iyy="0.001666666666666667" iyz="0.0" izz="0.001666666666666667"/>
    </inertial>
  </link>
  <joint name="camera_back_joint" type="fixed">
    <parent link="base_link"/>
    <child link="camera_back_link"/>
    <origin rpy="0 0 3.141592653589793" xyz="-1.0 0.0 0.3"/>
  </joint>
  <link name="camera_right_link">
    <visual>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
      <material name="Red">
        <color rgba="1.0 0.0 0.0 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <box size="0.1 0.1 0.1"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="1"/>
      <inertia ixx="0.001666666666666667" ixy="0.0" ixz="0.0" iyy="0.001666666666666667" iyz="0.0" izz="0.001666666666666667"/>
    </inertial>
  </link>
  <joint name="camera_right_joint" type="fixed">
    <parent link="base_link"/>
    <child link="camera_right_link"/>
    <origin rpy="0 0 4.71238898038469" xyz="0.0 -1.0 0.3"/>
  </joint>
  <gazebo reference="camera_left_link">
    <sensor name="camera_left" type="camera">
      <camera>
        <horizontal_fov>1.5708</horizontal_fov>
        <image>
          <width>320</width>
          <height>320</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>100</far>
        </clip>
      </camera>
      <always_on>1</always_on>
      <update_rate>30</update_rate>
    </sensor>
  </gazebo>
  <gazebo reference="camera_back_link">
    <sensor name="camera_back" type="camera">
      <camera>
        <horizontal_fov>1.5708</horizontal_fov>
        <image>
          <width>320</width>
          <height>320</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>100</far>
        </clip>
      </camera>
      <always_on>1</always_on>
      <update_rate>30</update_rate>
    </sensor>
  </gazebo>
  <gazebo reference="camera_right_link">
    <sensor name="camera_right" type="camera">
      <camera>
        <horizontal_fov>1.5708</horizontal_fov>
        <image>
          <width>320</width>
          <height>320</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>100</far>
        </clip>
      </camera>
      <always_on>1</always_on>
      <update_rate>30</update_rate>
    </sensor>
  </gazebo>
</robot>

I am using a ROS2 launch file and I get some error messages when I spawn the robot model with the wideanglecamera

robot_world.launch.py

import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration

def generate_launch_description():
    pkg_share = get_package_share_directory('simulation_launch')
    launch_file_dir = os.path.join(pkg_share, 'launch')
    pkg_gazebo_ros = get_package_share_directory('gazebo_ros')

    world_file = LaunchConfiguration('world_file')
    robot_model_file = LaunchConfiguration('robot_model_file')
    use_sim_time = LaunchConfiguration('use_sim_time')
    x_pose = LaunchConfiguration('x_pose')
    y_pose = LaunchConfiguration('y_pose')
    lockstep = LaunchConfiguration('lockstep')

    declare_world_file = DeclareLaunchArgument(
        name='world_file',
        default_value='',
        description='Path to world file'
    )
    declare_robot_model_file = DeclareLaunchArgument(
        name='robot_model_file',
        default_value='',
        description='Path to robot model file'
    )
    declare_use_sim_time = DeclareLaunchArgument(
        name='use_sim_time',
        default_value='false',
        description='Use simulation (Gazebo) clock if true'
    )
    declare_x_pose = DeclareLaunchArgument(
        name='x_pose',
        default_value='0.0',
        description='X-coordinate of robot spawn point'
    )
    declare_y_pose = DeclareLaunchArgument(
        name='y_pose',
        default_value='0.0',
        description='Y-coordinate of robot spawn point'
    )
    declare_lockstep = DeclareLaunchArgument(
        name='lockstep',
        default_value='true',
        description='Run Gazebo with lockstep if true'
    )

    gzserver_launch = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(pkg_gazebo_ros, 'launch', 'gzserver.launch.py')
        ),
        launch_arguments={
            'world': world_file,
            'lockstep': lockstep
        }.items()
    )
    gzclient_launch = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(pkg_gazebo_ros, 'launch', 'gzclient.launch.py')
        ),
        launch_arguments={'use_sim_time': use_sim_time}.items()
    )
    spawn_robot_launch = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(launch_file_dir, 'spawn_robot.launch.py')
        ),
        launch_arguments={
            'robot_model_file': robot_model_file,
            'x_pose': x_pose,
            'y_pose': y_pose
        }.items()
    )

    return LaunchDescription([
        declare_world_file,
        declare_robot_model_file,
        declare_use_sim_time,
        declare_x_pose,
        declare_y_pose,
        declare_lockstep,

        gzserver_launch,
        gzclient_launch,
        spawn_robot_launch
    ])

spawn_robot.launch.py (used by robot_world.launch.py)

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node

def generate_launch_description():
    robot_model_file = LaunchConfiguration('robot_model_file')
    x_pose = LaunchConfiguration('x_pose')
    y_pose = LaunchConfiguration('y_pose')

    declare_robot_model_file = DeclareLaunchArgument(
        name='robot_model_file',
        default_value='',
        description='Path to robot model file'
    )
    declare_x_position = DeclareLaunchArgument(
        name='x_pose', 
        default_value='0.0',
        description='Starting x position of the robot'
    )
    declare_y_position = DeclareLaunchArgument(
        name='y_pose', 
        default_value='0.0',
        description='Starting y position of the robot'
    )

    start_gazebo_ros_spawner = Node(
        package='gazebo_ros',
        executable='spawn_entity.py',
        arguments=[
            '-entity', 'test_bot',
            '-file', robot_model_file,
            '-x', x_pose,
            '-y', y_pose,
            '-z', '0.0'
        ],
        output='screen',
    )

    return LaunchDescription([
        declare_x_position,
        declare_y_position,
        declare_robot_model_file,
        start_gazebo_ros_spawner
    ])

The error messages in terminal output:

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [gzserver-1]: process started with pid [16256]
[INFO] [gzclient-2]: process started with pid [16258]
[INFO] [spawn_entity.py-3]: process started with pid [16260]
[spawn_entity.py-3] [INFO] [1700173470.981368833] [spawn_entity]: Spawn Entity started
[spawn_entity.py-3] [INFO] [1700173470.981789937] [spawn_entity]: Loading entity XML from file /home/dev_ws/src/simulation_launch/urdf/camera_test.urdf
[spawn_entity.py-3] [INFO] [1700173470.982671624] [spawn_entity]: Waiting for service /spawn_entity, timeout = 30
[spawn_entity.py-3] [INFO] [1700173470.983189810] [spawn_entity]: Waiting for service /spawn_entity
[spawn_entity.py-3] [INFO] [1700173472.237843372] [spawn_entity]: Calling service /spawn_entity
[gzserver-1] Node::Advertise(): Error advertising topic [default/test_bot/base_link/camera_back/image]. Did you forget to start the discovery service?
[gzserver-1] Node::Advertise(): Error advertising topic [default/test_bot/base_link/camera_left/image]. Did you forget to start the discovery service?
[gzserver-1] Node::Advertise(): Error advertising topic [default/test_bot/base_link/camera_right/image]. Did you forget to start the discovery service?
[spawn_entity.py-3] [INFO] [1700173472.485164696] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [test_bot]
[INFO] [spawn_entity.py-3]: process has finished cleanly [pid 16260]

I did some search on the error message, but could not find anything useful.

So my two questions are:

I am running ROS2 and Gazebo from a Docker container (I shared the host machine's XServer with the container for GUI)

This is how I installed Gazebo in the contianer

##### Setup Gazebo #####
# essential install packages
RUN apt-get update && apt-get install -q -y --no-install-recommends \
    dirmngr \
    gnupg2 \
    lsb-release \
    binutils \
    mesa-utils \
    kmod \
    x-window-system \
    curl \
    && rm -rf /var/lib/apt/lists/*

# setup keys
RUN apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-keys D2486D2DD83DB69272AFE98867170598AF249743

# setup sources.list
RUN . /etc/os-release \
    && echo "deb http://packages.osrfoundation.org/gazebo/$ID-stable `lsb_release -sc` main" > /etc/apt/sources.list.d/gazebo-latest.list

# install gazebo packages
RUN curl -sSL http://get.gazebosim.org | sh
Rudresh172 commented 6 months ago

Hey @Juhyung-L Did you find any solution to this? I am facing a similar issue. Although I can see the image in Rviz, it is very blurry, I have tried increasing the image resolution as well as the env_texture_size, but no changes.

Juhyung-L commented 6 months ago

Hi, sorry for the late response.

My problem was not blurry images. It was that I was using 3 wideanglecameras in Gazebo, which was making the simulation very slow. I still have not found out why using wideanglecameras is slow. So I just decided to use the regular camera.