ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

In Gazebo, my robot can't see AR tag

asked 2018-09-19 06:41:35 -0500

hyonietta gravatar image

updated 2018-09-19 18:28:25 -0500

jayess gravatar image

OS : Ubuntu 16.04 ROS : Kinetic Simulator : Gazebo

I made an AR tag model using Blender. (.dae) And make a SDF file for Gazebo. I can see the AR tag in Gazebo.

<?xml version='1.0'?>
<sdf version='1.6'>
    <model name='ar_tag_00'>
        <pose>4 0 0  0 0 0</pose>
        <static>true</static>
        <link name="ar_00">
            <visual name="visual">
                <pose>2 0 0 0 0 0</pose>
                <geometry>
                    <mesh><uri>model://ar_tags_for_turtlebot3_exp_house/meshes/ar_tag_00.dae</uri></mesh>
                </geometry>
            </visual>
        </link>
    </model>
</sdf>

But, my robot can't see the AR tag. It just see the box !!! In Rviz, it is same. Robot can't sense any obstacle(LIDAR). But, In camera, robot can see the box..

I don't know why. Please help me.

edit retag flag offensive close merge delete

Comments

If you link to some pictures hosted elsewhere I or someone else can embed them in the question.

lucasw gravatar image lucasw  ( 2018-09-19 13:04:10 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-09-19 17:10:36 -0500

dhood gravatar image

This be the perfect riddle fer Answer ROS Questions Like a Pirate Day!

If the model for yer ARRRRRR tag has a "visual", 'twill be detected by cameras. To be detected by other sensors, yer ARRRR tag needs to 'ave a "collision". The "collision" is wha' th' physics engine be usin' fer detectin' objects such as this.

An example be waitin' for ya at http://gazebosim.org/tutorials?tut=bu... .

This be how to visualise the collisions once ye add them to yer ARRRRRR tag: http://answers.gazebosim.org/question...

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2018-09-19 06:41:35 -0500

Seen: 485 times

Last updated: Sep 19 '18