Adding light source as a model in Groovy-Gazebo
I have been trying find an answer to this question for a very long time but I still haven't! "How to add light sources in the gazebo world dynamically ?" I am using ROS-Groovy (Gazebo 1.5.0).
In electric (pre-1.0 SDF) there was this <model:renderable>
option where I was able to spawn light source as a model after launch the gazebo world in any pose I wanted.
<?xml version="1.0" ?>
<robot name="light_balcony">
<link name="bulb_balcony">
<inertial>
<mass value="1" />
<com xyz="11.27 3.15 2.25" />
<inertia ixx="0" ixy="0.0" ixz="0.0" iyy="0" iyz="0.0" izz="0" />
</inertial>
<visual>
<origin xyz="11.27 3.15 2.25" rpy="0 0 0" /> <!-- definition of the visual postion of the object!! -->
<geometry>
<sphere radius="0.0001" />
</geometry>
</visual>
<collision>
<origin xyz="11.27 3.15 2.25" rpy="0 0 0" />
<geometry>
<sphere radius="0.0001" />
</geometry>
</collision>
</link>
<gazebo reference="bulb_balcony">
<model:renderable name="light_balcony">
<xyz>11.27 3.15 2.25</xyz>
<static>true</static>
<light>
<type>point</type>
<diffuseColor>0.1 0.1 0.1</diffuseColor>
<specularColor>.01 .01 .01</specularColor>
<attenuation>0.1 0.1 0.0001</attenuation>
<range>4</range>
</light>
</model:renderable>
</gazebo>
</robot>
When I switched to fuerte, it was no longer an option and even in groovy, I am not able to find a way out :( I am able to add a light to my world file but what I really want is adding it dynamically similar to adding a model. Taking advice from @AndreiHaidu and others (here, and many other pages), I tried a lot like adding
<include>
<uri>model://sun</uri>
<pose>0.3 0.2 5.0 0 0 0</pose>
</include>
or
<light type="directional" name="my_light">
<pose>0 0 30 0 0 0</pose>
<diffuse>.9 .9 .9 1</diffuse>
<specular>.1 .1 .1 1</specular>
<attenuation>
<range>20</range>
</attenuation>
<direction>0 0 -1</direction>
<cast_shadows>true</cast_shadows>
</light>
I have tried these in different sdf formats too. All threw errors. Finally when I tried this,
<gazebo version='1.0'>
<model name='apartment_floor0' static='1'>
<origin pose='-5 -5 0 0 0 0'/>
<link name='ow_2_body' gravity='1' self_collide='0' kinematic='0'>
<origin pose='0 0 0 0 0 0'/>
<collision name='ow_2_geom' laser_retro='0.000000'>
<origin pose='3.300000 0.150000 1.500000 0.000000 -0.000000 0.000000'/>
<geometry>
<box size='2.400000 0.300000 3.000000'/>
</geometry>
<surface>
<friction>
<ode mu='-1.000000' mu2='-1.000000' fdir1='0.000000 0.000000 0.000000' slip1='0.000000' slip2='0.000000'/>
</friction>
<bounce restitution_coefficient='0.000000' threshold='100000.000000'/>
<contact>
<ode soft_cfm='0.000000' soft_erp='0.200000' kp='1000000000000.000000' kd='1.000000' max_vel='100.000000' min_depth='0.001000'/>
</contact>
</surface>
</collision>
<visual name='ow_2_geom_visual' cast_shadows='1' laser_retro='0.000000' transparency='0.000000'>
<origin pose='6.850000 1.500000 1.500000 0.000000 -0.000000 1.570800'/>
<geometry>
<box size='2.400000 0.300000 3.000000'/>
</geometry>
<material script='Gazebo/White'/>
</visual>
</link>
</model>
<light name='my_light' type='directional'>
<pose>0.000000 0.000000 30.000000 0.000000 0.000000 0.000000</pose>
<diffuse>0.900000 0.900000 0.900000 1.000000</diffuse>
<specular>0.100000 0.100000 0.100000 1.000000</specular>
<attenuation>
<range>20.000000</range>
</attenuation>
<direction>0.000000 0.000000 -1.000000</direction>
<cast_shadows>0</cast_shadows>
</light>
</gazebo>
I did not get any error but I was only able to see the ow2body on the world and the light did not appear at all.
Is there any mistake I am doing that I am not seeing ? Is there any other way out or should I accept the cold truth that there is no way out ?
I repeat, I don't want to spawn it with the world, I want to spawn it as model after launching gazebo world. I am using ROS groovy now with gazebo 1.5 and I also have a standalone gazebo 1.8 installed.
Thanks,
Prasanna
Asked by prasanna.kumar on 2013-06-18 06:57:45 UTC
Answers
Hi,
in the ~/.gazebo folder you have a model called Sun
(which you can get from the gazebo model database).
You can insert that as a model in the world (from the Insert Tab for example), and it acts as a light source.
Example with the sun: https://vimeo.com/68620660
Cheers, Andrei
Asked by AndreiHaidu on 2013-06-18 10:03:24 UTC
Comments
Hi, I know that I can insert light model from the insert tab on the GUI, I need to do it programatically. I have an apartment model and each room has a light bulb. When I run rosrun angen_apps light_control ON workroom, a light source should be spawned inside the bulb model(giving the impression of switching ON a light bulb). I was doing this in ROS-Electric using the above mentioned URDF model but I am not able to do the same in Fuerte or Groovy. Can you tell me a way to do it programatically ?
Asked by prasanna.kumar on 2013-06-18 15:38:23 UTC
@prasanna.kumar: Did you come around solving this problem? I was tracking this issue: https://bitbucket.org/osrf/gazebo/pull-requests/2807/add-light-as-child-of-link/diff%3C/p%3E which allows me to spawn spotlights to robot links at the time of world creation but I wasn't able to switch them off and on at will. Any help would be really appreciated. I'm working with turtlebots in Gazebo 8 and ROS Kinetic.
Asked by cgnarendiran on 2018-04-25 09:26:18 UTC
Hi,
ok I understand the idea now, currently I don't have access to a PC with gazebo installed to test a code snippet, but here is the idea how you should try to implement it via a plugin:
Here is the Light class with all the methods you need to control the light.
You should be able to access it with this function. After accessing the Scene.
In order to access the visual part of gazebo (eg Scene) you need to create a visual plugin, this way you get access to the GUI and the rendering engine. Here is a tutorial how to create such a plugin.
If you still have problems implementing it, let me know and I could write some code snippets.
Cheers, Andrei
Asked by AndreiHaidu on 2013-06-18 17:43:43 UTC
Comments
Hello, this page has been lost. Can you still provide relevant information?
Asked by Simple on 2021-09-06 22:33:17 UTC
Hello Andrei,
I have the same problem. I want to implement a node that upon receiving a message (e.g. a command from a robot) spawns a light within an existing gazebo world. This is doable using the GUI, but I want to achieve the same results from a node. The tutorial about the plugin seems to explain how to insert elements in the GUI which is not the case for us.
Do you have any suggestion?
Thanks,
M
Asked by Modo on 2013-07-24 11:00:34 UTC
Comments
Hey, have you with the answer I gave before? Creating a visual plugin and getting the light model with
LightPtr gazebo::rendering::Scene::GetLight
and after that you can control the lights functionalities.
Asked by AndreiHaidu on 2013-07-24 11:20:54 UTC
Hi Andrei, the problem is that I want to create the light at run time. You can even imagine that this procedure should run even without displaying the GUI
Asked by Modo on 2013-07-24 11:26:14 UTC
A light can be dynamically spawned into a world by publishing a msgs::Light message to the "~/light" topic.
Asked by nkoenig on 2013-07-24 11:14:14 UTC
Comments
Thanks, is this the case also for Gazebo 1.0.2?
Asked by Modo on 2013-07-24 11:55:29 UTC
Most likely not. Gazebo 1.0.2 is deprecated.
Asked by nkoenig on 2013-07-24 12:19:04 UTC
Yes I know. Unfortunately we have built a stack on Fuerte because we extensively use turtlebots in these simulated environments. We already have ported lights, sensors and actuators to the latest stand alone version of gazebo but we need to run simulations with the turtlebot, i.e. fuerte. Are you able to tell me where looking for? May be to the code of the gui? I need to do that programmatically. Thanks
Asked by Modo on 2013-07-24 12:58:32 UTC
Comments