Where's my ball? Display issue.
I have managed to add a static ball and table to the baxter world. Ubuntu 14.04 gazebo 2.2
However, it is not appearing right in the baxter camera.
Here is how it looks in gazebo.
But taking the camera view half of it is missing.
Any suggestions on a resolution and what I am missing?
Here's my world.
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<physics type="ode">
<real_time_update_rate>1000.0</real_time_update_rate>
<gravity>
0.0 0.0 -9.81
</gravity>
</physics>
<model name='unit_sphere_1'>
<pose>2 -0.554543 0.5 0 -0 0</pose>
<link name='link'>
<inertial>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.025</radius>
</sphere>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<bounce/>
<friction>
<ode/>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.025</radius>
</sphere>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Green</name>
</script>
</material>
</visual>
<velocity_decay>
<linear>0</linear>
<angular>0</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
<static>0</static>
</model>
<model name='table'>
<static>1</static>
<link name='link'>
<collision name='surface'>
<pose>0 0 1 0 -0 0</pose>
<geometry>
<box>
<size>1.5 0.8 0.03</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>0.6</mu>
<mu2>0.6</mu2>
</ode>
</friction>
<bounce/>
<contact>
<ode/>
</contact>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual1'>
<pose>0 0 1 0 -0 0</pose>
<geometry>
<box>
<size>1.5 0.8 0.03</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name='front_left_leg'>
<pose>0.68 0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<bounce/>
<friction>
<ode/>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<visual name='front_left_leg'>
<pose>0.68 0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name='front_right_leg'>
<pose>0.68 -0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<bounce/>
<friction>
<ode/>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<visual name='front_right_leg'>
<pose>0.68 -0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name='back_right_leg'>
<pose>-0.68 -0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<bounce/>
<friction>
<ode/>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<visual name='back_right_leg'>
<pose>-0.68 -0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name='back_left_leg'>
<pose>-0.68 0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<bounce/>
<friction>
<ode/>
</friction>
<contact>
<ode/>
</contact>
</surface>
</collision>
<visual name='back_left_leg'>
<pose>-0.68 0.38 0.5 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>1</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<velocity_decay>
<linear>0</linear>
<angular>0</angular>
</velocity_decay>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<gravity>1</gravity>
</link>
<pose>2 -0.586205 0 0 -0 0</pose>
</model>
<state world_name='default'>
<sim_time>182 374000000</sim_time>
<real_time>99 169468607</real_time>
<wall_time>1465547225 421086341</wall_time>
<model name='ground_plane'>
<pose>0 0 0 0 -0 0</pose>
<link name='link'>
<pose>0 0 0 0 -0 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
<model name='table'>
<pose>1.66091 0.334884 0.000723 -0.00213 8.8e-05 -1.52964</pose>
<link name='link'>
<pose>1.66091 0.334884 0.000723 -0.00213 8.8e-05 -1.52964</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
<model name='unit_sphere_1'>
<pose>1.68129 0.132237 1.04068 1e-06 0.005781 0</pose>
<link name='link'>
<pose>1.68129 0.132237 1.04068 1e-06 0.005781 0</pose>
<velocity>0 0 0 0 -0 0</velocity>
<acceleration>0 0 0 0 -0 0</acceleration>
<wrench>0 0 0 0 -0 0</wrench>
</link>
</model>
</state>
</world>
</sdf>
Asked by PerceptualRobots on 2016-06-10 05:40:32 UTC
Answers
This looks like a bug. Maybe it's a good idea to upgrade your version of Gazebo. I just tried it on Gazebo 7 and it shows up properly.
Note that Gazebo 2 has reached its end of life in January 2016, so it shouldn't be getting any bug fixes.
Asked by chapulina on 2016-06-10 10:06:40 UTC
Comments
Thanks, but baxter is only supported on v2.2 as I understand it. I'll check with them if I can upgrade.
Asked by PerceptualRobots on 2016-06-10 11:15:02 UTC
Btw, would you post the code for your example, I'd like to try it out on a secondary machine where I can upgrade gazebo?
Asked by PerceptualRobots on 2016-06-12 06:22:51 UTC
Oh I just opened your world and inserted a camera from the left panel's Insert tab.
Asked by chapulina on 2016-06-12 14:02:39 UTC
Just tried that but it just falls to the floor, how do you keep it in mid-air? If I can do that with the ball I won't need the table.
Asked by PerceptualRobots on 2016-06-13 15:02:37 UTC
You can make it static if you don't want any forces to be applied on it. add <static>true</static>
to the model.
Asked by chapulina on 2016-06-13 15:13:47 UTC
Comments