Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SimPause() not pausing physics #4174

Closed
sguttikon opened this issue Nov 20, 2021 · 4 comments · Fixed by #4175
Closed

SimPause() not pausing physics #4174

sguttikon opened this issue Nov 20, 2021 · 4 comments · Fixed by #4175

Comments

@sguttikon
Copy link

sguttikon commented Nov 20, 2021

Bug report

  • AirSim Version/#commit: Master Branch
  • UE/Unity version: UnrealEngine_4.25
  • autopilot version:
  • OS Version: Ubuntu 18.04.6 LTS

What's the issue you encountered?

As you can see from the output, when simulation is paused - the offset between car and camera position increased after sleep.
Expected: the relative position should almost remain constant since vehicle moving in straight path and simulation is paused.
May be this is an old/known issue, simPause() seems to no pausing physics engine or these is some other issue.

Settings

{
  "SeeDocsAt": "https://github.com/Microsoft/AirSim/blob/master/docs/settings.md",
  "SettingsVersion": 1.2,
  "SimMode": "Car"
}

How can the issue be reproduced?

Code Snippet:

#--- hello_car.py ---

#!/usr/bin/env python3
# -*- coding: utf-8 -*-

import airsim
import time
import numpy as np

# connect to the AirSim simulator
client = airsim.CarClient()
client.confirmConnection()
client.enableApiControl(True)
car_controls = airsim.CarControls()

for _ in range(10):
    # set the controls for car
    car_controls.throttle = -0.5
    car_controls.is_manual_gear = True;
    car_controls.manual_gear = -1
    client.setCarControls(car_controls)

    # let car drive a bit
    time.sleep(1)

client.simPause(True)
car_position1 = client.getCarState().kinematics_estimated.position
img_position1 = client.simGetImages([airsim.ImageRequest(0, airsim.ImageType.Scene)])[0].camera_position
print(f"Before pause: {car_position1.x_val - img_position1.x_val}, {car_position1.y_val - img_position1.y_val}, {car_position1.z_val - img_position1.z_val}")

time.sleep(10)

car_position2 = client.getCarState().kinematics_estimated.position
img_position2 = client.simGetImages([airsim.ImageRequest(0, airsim.ImageType.Scene)])[0].camera_position
print(f"After pause: {car_position2.x_val - img_position2.x_val}, {car_position2.y_val - img_position2.y_val}, {car_position2.z_val - img_position2.z_val}")
client.simPause(False)

Include full error message in text form

$ python3 hello_car.py 
Connected!
Client Ver:1 (Min Req: 1), Server Ver:1 (Min Req: 1)

Before pause: -1.8311004638671875, -0.010279476642608643, 0.9998747706413269
After pause: -2.0000457763671875, -0.011233329772949219, 0.9998047351837158

What's better than filing an issue? Filing a pull request :).

@rajat2004
Copy link
Contributor

Thanks a lot for the reproducible example! Could you try out #4175 and see if it fixes the problem for you?

@sguttikon
Copy link
Author

Thank you @rajat2004, it seems your changes fixed this issue. :)

@jonyMarino
Copy link
Collaborator

@suresh-guttikonda This somehow solves the issue you had in driving the car with the keyboard after calling simPause() as you described in #4171?

@sguttikon
Copy link
Author

@jonyMarino Unfortunately it didn't fix the #4171, i tried the code snippet as mentioned in that issue. But still I can see x-position difference between left, center, right cameras even though i am using stereo camera setup

code snippet

#!/usr/bin/env python3
# -*- coding: utf-8 -*-

import airsim
import time

# connect to the AirSim simulator
client = airsim.CarClient()
client.confirmConnection()
client.enableApiControl(True)
car_controls = airsim.CarControls()

while True:
    # get state of the car
    car_state = client.getCarState()
    print("Speed %d, Gear %d" % (car_state.speed, car_state.gear))

    # set the controls for car
    car_controls.throttle = -0.5
    car_controls.is_manual_gear = True;
    car_controls.manual_gear = -1
    client.setCarControls(car_controls)

    # let car drive a bit
    time.sleep(1)

    client.simPause(True)
    # get camera images from the car
    responses = client.simGetImages([
        airsim.ImageRequest("front_left_custom", airsim.ImageType.Scene),
        airsim.ImageRequest("front_center_custom", airsim.ImageType.Scene),
        airsim.ImageRequest("front_right_custom", airsim.ImageType.Scene)
    ])

    # do something with images
    print(f"Left Image   : {responses[0].time_stamp} {responses[0].camera_position}")
    print(f"Center Image : {responses[1].time_stamp} {responses[1].camera_position}")
    print(f"Right Image  : {responses[2].time_stamp} {responses[2].camera_position}")
    print("-----------------------")
    client.simPause(False)

output:

Speed 0, Gear 0
Left Image   : 1637680881635593000 <Vector3r> {   'x_val': 1.276526689529419,
    'y_val': -0.500444233417511,
    'z_val': -1.0125737190246582}
Center Image : 1637680881639327000 <Vector3r> {   'x_val': 1.2766900062561035,
    'y_val': -0.00044429057743400335,
    'z_val': -1.0125446319580078}
Right Image  : 1637680881642682000 <Vector3r> {   'x_val': 1.2768532037734985,
    'y_val': 0.49955567717552185,
    'z_val': -1.0125157833099365}
.....
Speed -5, Gear -1
Left Image   : 1637680508018565000 <Vector3r> {   'x_val': -50.67403793334961,
    'y_val': -0.5161873698234558,
    'z_val': -1.0174293518066406}
Center Image : 1637680508020641000 <Vector3r> {   'x_val': -50.67300033569336,
    'y_val': -0.016188468784093857,
    'z_val': -1.0174232721328735}
Right Image  : 1637680508023466000 <Vector3r> {   'x_val': -50.671966552734375,
    'y_val': 0.4838104546070099,
    'z_val': -1.017417311668396}

....
Speed -4, Gear -1
Left Image   : 1637680514926896000 <Vector3r> {   'x_val': -74.15702819824219,
    'y_val': -0.31434252858161926,
    'z_val': -1.0183379650115967}
Center Image : 1637680514932230000 <Vector3r> {   'x_val': -74.15306091308594,
    'y_val': 0.18564172089099884,
    'z_val': -1.0182714462280273}
Right Image  : 1637680514936044000 <Vector3r> {   'x_val': -74.14909362792969,
    'y_val': 0.6856259703636169,
    'z_val': -1.018204927444458}

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging a pull request may close this issue.

3 participants