Gazebo | Ignition | Community
Ask Your Question
0

How to change gravity in python code/questions on reseting the model

asked 2017-09-01 21:06:22 -0600

bt gravatar image

Hey guys,

I have a few questions, sorry if there are simple answers but I couldn't find them in any of the tutorials.

I am trying to create a simple walker with 8 joints to use with reinforcement learning algorithms, and so need to reset the model quickly after each episode.

The problem I am having is when I do a service call to reset the world and the model, the plugins need to restart (camera, imu, joint_states) and they take up to minutes to publish again (which is not ideal given the many episodes needed).

So instead I am trying to reset the model_state at the end of the episode back to its starting position. The problem with this is getting the joint positions back to 0.0. I am using the joint_position_controller/command as outlined in the tutorials but they obviously take some time to get back to these positions, and this time seems to be affected by gravity (even after turning up the PID values).

I thought that if I changed gravity to zero, reset the model_state, then I could send the joint commands, and then turn gravity back on.

My questions:

  • How do I reset gravity? Am I missing a gazebo_msg that I need to include in the service call? What I have so far:

from gazebo_msgs.srv import SetPhysicsProperties
set_gravity = rospy.ServiceProxy('/gazebo/set_physics_properties', SetPhysicsProperties)
set_physics = SetPhysicsProperties() # how do I set gravity? 
set_gravity(set_physics) # this call does not work (not expecting SetPhysicsProperties object)
  • Is there a better way of get the joints to go to a desired position? Currently I have to wait for the joints to reach their positions (determined by process_value_dot because some of the joints don't reach their positions when the robot has fallen over, I assume due to effort constraints):

for i in range(NUM_JOINTS):
    joints[i].publish(0.0)

    data = None
    while not rospy.is_shutdown():
        try:
            data = rospy.wait_for_message('/mybot/joint' + str(i) + '_position_controller/state', JointControllerState, timeout=1)
            if abs(data.process_value_dot) < 0.01:
                break
        except:
            pass
        time.sleep(0.001)

  • This approach I am trying seems very convoluted for simply reseting the model without restarting the plugins. Is there a better way to reset the model quickly (keeping in mind the /gazebo/reset_simulation service call stops the plugins)?

Thanks for your time guys.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2017-10-02 08:03:43 -0600

Duckfrost gravatar image

I would like to complement the answer given by @bt.

Here you have the video that explains all the process: VideoAnswer

In this case I have created a python script (change_gravity.py) that generates a class that controlles gravity in Gazebo. It has a testing function that changes the gravity two various configurations sequentially to see the effect.

I use the different gazebo services to pause, unpause , reset and set the Gazebo Physiscs.

I have used a simple URDF difined object called simple_box.

Here you have all the main files necessary:

The Script that changes the gravity->change_gravity.py

Main that launches everything->main.launch

Launch to spawn the simple box->spawn_simple_box.launch

Launch to spawn a URDF model->spawn_robot_urdf.launch

Model of the simple box ->simple_box.urdf

The simple world with normal gravity simple.world

Hope this helps.

edit flag offensive delete link more

Comments

Thank you for in-depth video and response! I don't have enough rep to upvote

bt gravatar imagebt ( 2017-10-02 15:49:05 -0600 )edit
0

answered 2017-09-11 17:13:40 -0600

bt gravatar image

To set the gravity in code:


    import gazebo_msgs.msg
    from std_msgs.msg import Float64    

    set_gravity = rospy.ServiceProxy('/gazebo/set_physics_properties', SetPhysicsProperties)

    time_step = Float64(0.001)
    max_update_rate = Float64(1000.0)
    gravity = geometry_msgs.msg.Vector3()
    gravity.x = 0.0
    gravity.y = 0.0
    gravity.z = 0.0
    ode_config = gazebo_msgs.msg.ODEPhysics()
    ode_config.auto_disable_bodies = False
    ode_config.sor_pgs_precon_iters = 0
    ode_config.sor_pgs_iters = 50
    ode_config.sor_pgs_w = 1.3
    ode_config.sor_pgs_rms_error_tol = 0.0
    ode_config.contact_surface_layer = 0.001
    ode_config.contact_max_correcting_vel = 0.0
    ode_config.cfm = 0.0
    ode_config.erp = 0.2
    ode_config.max_contacts = 20
    set_gravity(time_step.data, max_update_rate.data, gravity, ode_config)
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2017-09-01 21:06:22 -0600

Seen: 2,847 times

Last updated: Oct 02 '17