gazebo/SetPhysicsProperties Service

File: gazebo/SetPhysicsProperties.srv

# sets pose and twist of a link.  All children link poses/twists of the URDF tree will be updated accordingly
float64 time_step                  # dt in seconds
bool pause                         # pause physics
float64 max_update_rate            # throttle maximum physics update rate
geometry_msgs/Vector3 gravity      # gravity vector (e.g. earth ~[0,0,-9.81])
gazebo/ODEPhysics ode_config       # configurations for ODE
---
bool success                       # return true if set wrench successful
string status_message              # comments if available

Expanded Definition

float64 time_step
bool pause
float64 max_update_rate
geometry_msgs/Vector3 gravity
    float64 x
    float64 y
    float64 z
gazebo/ODEPhysics ode_config
    bool auto_disable_bodies
    uint32 sor_pgs_iters
    float64 sor_pgs_w
    float64 contact_surface_layer
    float64 contact_max_correcting_vel
    float64 cfm
    float64 erp
    uint32 max_contacts

bool success
string status_message