Gazebo | Ignition | Community
Ask Your Question
0

i am trying to load my depth cam model in gazebo,and it is falling down immediately

asked 2022-05-15 10:10:12 -0600

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

the model


<sdf version="1.5">
<model name="my_model">
    <link name="camera_depth_frame">
        <pose>0.12 0 0.65 -1.5708 0 -1.5708</pose>
    </link>

    <link name="camera_link">
         <pose>0.12 0 0.65 0 0 0</pose>

        <visual name="camera_visual">
            <pose>-0.005 0 0 0 0 0</pose>
            <geometry>
                <box>
                    <size>0.015 0.08 0.022</size>
                </box>
            </geometry>
            <material>
                <ambient>0 0 0 1.0</ambient>
                <diffuse>0 0 0 1.0</diffuse>
                <specular>0.0 0.0 0.0 1.0</specular>
                <emissive>0.0 0.0 0.0 1.0</emissive>
            </material>
        </visual>    

        <sensor name="depth_camera" type="camera">
            <always_on>true</always_on>
            <visualize>false</visualize>
            <update_rate>5</update_rate>
            <camera name="camera">
                <horizontal_fov>1.02974</horizontal_fov>
                <image>
                    <width>640</width>
                    <height>480</height>
                    <format>R8G8B8</format>
                </image>
                <clip>
                    <near>0.02</near>
                    <far>10</far>
                </clip>
                <noise>
                    <type>gaussian</type>
                    <!-- Noise is sampled independently per pixel on each frame.
                           That pixel's noise value is added to each of its color
                           channels, which at that point lie in the range [0,1]. -->
                    <mean>0.0</mean>
                    <stddev>0.007</stddev>
                </noise>
            </camera>
            <plugin name="depth_camera_controller" filename="libgazebo_ros_camera.so">
                <camera_name>depth_camera</camera_name>
                <frame_name>camera_depth_frame</frame_name>
                <hack_baseline>0</hack_baseline>
                <min_depth>0.001</min_depth>  
            </plugin>
        </sensor>
    </link>
</model> 
</sdf>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-05-18 05:00:59 -0600

Veerachart gravatar image

Since the model's static is not given, it's false, meaning that gravity will pull it down, and your camera ends up free-falling. A collision can help stopping it on the ground (if you have a ground with collision in your world).

Also you have 2 links in your model, if they are not static, you need to connect them with a joint (can be a fixed joint). Otherwise, one link may also fall away from the other if only one of them has a collision to hit the ground.

Note that if you plan to include this model into another non-static model later, the static flag will be overwritten, and the 2 links will be disconnected if you choose to stop them from falling by setting it static.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-05-15 10:10:12 -0600

Seen: 137 times

Last updated: May 18 '22