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

Revision history [back]

Hi @jdastoor3

Apologies for suggesting pygazebo, I was able to make it work but there are many bugs. Instead, I went over again and I think using Gazebo Services is the way to go:

After you launch gazebo using roslaunch gazebo_ros empty_world.launch in another terminal you can check services available: rosservice list If you look into: rosservice info /gazebo/set_light_properties you will get:

Node: /gazebo

URI: rosrpc://127....
Type: gazebo_msgs/SetLightProperties
Args: light_name cast_shadows diffuse specular attenuation_constant attenuation_linear attenuation_quadratic direction pose

And if you look further into this by rossrv show gazebo_msgs/SetLightProperties

string light_name
bool cast_shadows
std_msgs/ColorRGBA diffuse
  float32 r
  float32 g
  float32 b
  float32 a
std_msgs/ColorRGBA specular
  float32 r
  float32 g
  float32 b
  float32 a
float64 attenuation_constant
float64 attenuation_linear
float64 attenuation_quadratic
geometry_msgs/Vector3 direction
  float64 x
  float64 y
  float64 z
geometry_msgs/Pose pose
  geometry_msgs/Point position
    float64 x
    float64 y
    float64 z
  geometry_msgs/Quaternion orientation
    float64 x
    float64 y
    float64 z
    float64 w
---
bool success
string status_message

To access with Python, I wrote this script:

import time
import rospy

from gazebo_msgs.srv import SetPhysicsProperties, SetPhysicsPropertiesRequest
from gazebo_msgs.srv import SetLightProperties, SetLightPropertiesRequest
from geometry_msgs.msg import Pose, Quaternion
from geometry_msgs.msg import Vector3
from std_msgs.msg import Float64    
from std_msgs.msg import ColorRGBA  
from std_srvs.srv import Empty 

service_name = '/gazebo/set_light_properties'
rospy.loginfo("Waiting for service " + str(service_name))
rospy.wait_for_service(service_name)
rospy.loginfo("Service Found "+str(service_name))

set_light = rospy.ServiceProxy(service_name, SetLightProperties)

light_name = 'sun'
cast_shadows = True

difuse = ColorRGBA()
difuse.r = float(204/255)
difuse.g = float(204/255)
difuse.b = float(204/255)
difuse.a = float(255/255)

specular = ColorRGBA()
specular.r = float(51/255)
specular.g = float(51/255)
specular.b = float(51/255)
specular.a = float(255/255)

attenuation_constant = 0.90
attenuation_linear = 0.01
attenuation_qudratic = 0.00

direction = Vector3()
direction.x = -0.483368
direction.y = 0.096674
direction.z = -0.870063

pose = Pose()
pose.position.x = 0.00
pose.position.y = 0.00
pose.position.z = 10.00

pose.orientation.x = 0.00
pose.orientation.y = 0.00
pose.orientation.z = 0.00
pose.orientation.w = 1.00

response = set_light(light_name, cast_shadows, difuse, specular, attenuation_constant, attenuation_linear, attenuation_qudratic, direction, pose)

print(response)

I am using the default settings that you can see in Gazebo:

image description

Hope this helps you, then you can change light conditions or other properties to set fog.

Hi @jdastoor3

Apologies for suggesting pygazebo, I was able to make it work but there are many bugs. Instead, I went over again and I think using Gazebo Services is the way to go:

After you launch gazebo using roslaunch gazebo_ros empty_world.launch in another terminal you can check services available: rosservice list If you look into: rosservice info /gazebo/set_light_properties you will get:

Node: /gazebo

/gazebo

    URI: rosrpc://127....
 Type: gazebo_msgs/SetLightProperties
 Args: light_name cast_shadows diffuse specular attenuation_constant attenuation_linear attenuation_quadratic direction pose

And if you look further into this by rossrv show gazebo_msgs/SetLightProperties

string light_name
bool cast_shadows
std_msgs/ColorRGBA diffuse
  float32 r
  float32 g
  float32 b
  float32 a
std_msgs/ColorRGBA specular
  float32 r
  float32 g
  float32 b
  float32 a
float64 attenuation_constant
float64 attenuation_linear
float64 attenuation_quadratic
geometry_msgs/Vector3 direction
  float64 x
  float64 y
  float64 z
geometry_msgs/Pose pose
  geometry_msgs/Point position
    float64 x
    float64 y
    float64 z
  geometry_msgs/Quaternion orientation
    float64 x
    float64 y
    float64 z
    float64 w
---
bool success
string status_message

To access with Python, I wrote this script:

import time
import rospy

from gazebo_msgs.srv import SetPhysicsProperties, SetPhysicsPropertiesRequest
from gazebo_msgs.srv import SetLightProperties, SetLightPropertiesRequest
from geometry_msgs.msg import Pose, Quaternion
from geometry_msgs.msg import Vector3
from std_msgs.msg import Float64    
from std_msgs.msg import ColorRGBA  
from std_srvs.srv import Empty 

service_name = '/gazebo/set_light_properties'
rospy.loginfo("Waiting for service " + str(service_name))
rospy.wait_for_service(service_name)
rospy.loginfo("Service Found "+str(service_name))

set_light = rospy.ServiceProxy(service_name, SetLightProperties)

light_name = 'sun'
cast_shadows = True

difuse = ColorRGBA()
difuse.r = float(204/255)
difuse.g = float(204/255)
difuse.b = float(204/255)
difuse.a = float(255/255)

specular = ColorRGBA()
specular.r = float(51/255)
specular.g = float(51/255)
specular.b = float(51/255)
specular.a = float(255/255)

attenuation_constant = 0.90
attenuation_linear = 0.01
attenuation_qudratic = 0.00

direction = Vector3()
direction.x = -0.483368
direction.y = 0.096674
direction.z = -0.870063

pose = Pose()
pose.position.x = 0.00
pose.position.y = 0.00
pose.position.z = 10.00

pose.orientation.x = 0.00
pose.orientation.y = 0.00
pose.orientation.z = 0.00
pose.orientation.w = 1.00

response = set_light(light_name, cast_shadows, difuse, specular, attenuation_constant, attenuation_linear, attenuation_qudratic, direction, pose)

print(response)

I am using the default settings that you can see in Gazebo:

image description

Hope this helps you, then you can change light conditions or other properties to set fog.

Hi @jdastoor3

Apologies for suggesting pygazebo, I was able to make it work but there are many bugs. Instead, I went over again and I think using Gazebo Services is the way to go:

After you launch gazebo using roslaunch gazebo_ros empty_world.launch in another terminal you can check services available: rosservice list If you look into: rosservice info /gazebo/set_light_properties you will get:

Node: /gazebo

    URI: rosrpc://127....
    Type: gazebo_msgs/SetLightProperties
    Args: light_name cast_shadows diffuse specular attenuation_constant attenuation_linear attenuation_quadratic direction pose

And if you look further into this by rossrv show gazebo_msgs/SetLightProperties

string light_name
bool cast_shadows
std_msgs/ColorRGBA diffuse
  float32 r
  float32 g
  float32 b
  float32 a
std_msgs/ColorRGBA specular
  float32 r
  float32 g
  float32 b
  float32 a
float64 attenuation_constant
float64 attenuation_linear
float64 attenuation_quadratic
geometry_msgs/Vector3 direction
  float64 x
  float64 y
  float64 z
geometry_msgs/Pose pose
  geometry_msgs/Point position
    float64 x
    float64 y
    float64 z
  geometry_msgs/Quaternion orientation
    float64 x
    float64 y
    float64 z
    float64 w
---
bool success
string status_message

To access with Python, I wrote this script:

#!/usr/bin/env python
import time
import rospy

from gazebo_msgs.srv import SetPhysicsProperties, SetPhysicsPropertiesRequest
from gazebo_msgs.srv import SetLightProperties, SetLightPropertiesRequest
from geometry_msgs.msg import Pose, Quaternion
from geometry_msgs.msg import Vector3
from std_msgs.msg import Float64    
from std_msgs.msg import ColorRGBA  
from std_srvs.srv import Empty 

service_name = '/gazebo/set_light_properties'
rospy.loginfo("Waiting for service " + str(service_name))
rospy.wait_for_service(service_name)
rospy.loginfo("Service Found "+str(service_name))

set_light = rospy.ServiceProxy(service_name, SetLightProperties)

light_name = 'sun'
cast_shadows = True

difuse = ColorRGBA()
difuse.r = float(204/255)
difuse.g = float(204/255)
difuse.b = float(204/255)
difuse.a = float(255/255)

specular = ColorRGBA()
specular.r = float(51/255)
specular.g = float(51/255)
specular.b = float(51/255)
specular.a = float(255/255)

attenuation_constant = 0.90
attenuation_linear = 0.01
attenuation_qudratic = 0.00

direction = Vector3()
direction.x = -0.483368
direction.y = 0.096674
direction.z = -0.870063

pose = Pose()
pose.position.x = 0.00
pose.position.y = 0.00
pose.position.z = 10.00

pose.orientation.x = 0.00
pose.orientation.y = 0.00
pose.orientation.z = 0.00
pose.orientation.w = 1.00

response = set_light(light_name, cast_shadows, difuse, specular, attenuation_constant, attenuation_linear, attenuation_qudratic, direction, pose)

print(response)

I am using the default settings that you can see in Gazebo:

image description

Hope this helps you, then you can change light conditions or other properties to set fog.