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

Camera positions is not synchronized across multiple cameras #4171

Open
sguttikon opened this issue Nov 19, 2021 · 3 comments
Open

Camera positions is not synchronized across multiple cameras #4171

sguttikon opened this issue Nov 19, 2021 · 3 comments

Comments

@sguttikon
Copy link

sguttikon commented Nov 19, 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?

If i am requesting images at 10 Hz and pausing/unpausing as instructed in image_apis, i am not able to move the car with keyboard.
Its very annoying and there are several bugs/issues still open for couple of years #2784 still there is no permanent solution and AirSim team didn't provide update on bug till now. I tried other simulator like Carla which is also based on UE, where it is able to sync correctly across multiple images without any issue !!!

I am opening this new issue/bug to bring this to attention for developers.

Settings

{
  "SeeDocsAt": "https://github.com/Microsoft/AirSim/blob/master/docs/settings.md",
  "SettingsVersion": 1.2,
  "SimMode": "Car",
  "ViewMode": "SpringArmChase",
  "ClockSpeed": 1.0,
  "Vehicles": {
    "drone_1": {
      "VehicleType": "PhysXCar",
      "DefaultVehicleState": "Armed",
      "EnableCollisionPassthrogh": false,
      "EnableCollisions": true,
      "AllowAPIAlways": true,
      "Sensors": {
        "Gps": {
          "SensorType": 3,
          "Enabled" : true
        },
        "Barometer": {
          "SensorType": 1,
          "Enabled" : true
        },
        "Magnetometer": {
          "SensorType": 4,
          "Enabled" : true
        },
        "Imu" : {
          "SensorType": 2,
          "Enabled": true
        },        
        "LidarCustom": {
          "SensorType": 6,
          "Enabled": true,
          "NumberOfChannels": 16,
          "PointsPerSecond": 10000,
          "X": 0,
          "Y": 0,
          "Z": -1.5,
          "DrawDebugPoints": true,
          "DataFrame": "SensorLocalFrame"
        }
      },
      "Cameras": {
        "front_center_custom": {
          "CaptureSettings": [
            {
              "PublishToRos": 1,
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 27,
              "DepthOfFieldFstop": 2.8,
              "DepthOfFieldFocalDistance": 200.0, 
              "DepthOfFieldFocalRegion": 200.0,
              "TargetGamma": 1.5
            }
          ],
          "X": 1.75, "Y": 0, "Z": -1.25,
          "Pitch": 0, "Roll": 0, "Yaw": 0
        },
        "front_left_custom": {
          "CaptureSettings": [
            {
              "PublishToRos": 1,
              "ImageType": 0,
              "Width": 672,
              "Height": 376,
              "FOV_Degrees": 90,
              "TargetGamma": 1.5
            }
          ],
          "X": 1.75, "Y": -0.5, "Z": -1.25,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        },
        "front_right_custom": {
          "CaptureSettings": [
            {
              "PublishToRos": 1,
              "ImageType": 0,
              "Width": 672,
              "Height": 376,
              "FOV_Degrees": 90,
              "TargetGamma": 1.5
            }
          ],
          "X": 1.75, "Y": 0.5, "Z": -1.25,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        }
      },
      "X": 0, "Y": 0, "Z": 0,
      "Pitch": 0, "Roll": 0, "Yaw": 0
    }
  },
  "SubWindows": [
    {"WindowID": 0, "ImageType": 0, "CameraName": "front_left_custom", "Visible": false},
    {"WindowID": 1, "ImageType": 0, "CameraName": "front_center_custom", "Visible": false},
    {"WindowID": 2, "ImageType": 0, "CameraName": "front_right_custom", "Visible": false}
  ]
}

How can the issue be reproduced?

    // update left+right images from airsim_client_ every nth sec
    void image_response_cb(const ros::TimerEvent& event) {
      // airsim_client_.simPause(true);
      std::vector<ImageRequest> request = {
        ImageRequest("front_left_custom", ImageType::Scene),
        ImageRequest("front_center_custom", ImageType::Scene),
        ImageRequest("front_right_custom", ImageType::Scene)
      };
      const std::vector<ImageResponse>& response = airsim_client_.simGetImages(request);
      // airsim_client_.simPause(false);
      std::cout << "Left Image  [" << left_cnt_ << "]: " <<
        convert_airsim_timestamp(response[0].time_stamp).count() << std::endl <<
        response[0].camera_position << std::endl;
      left_cnt_ += 1;
      std::cout << "Center Image[" << center_cnt_ << "]: " <<
        convert_airsim_timestamp(response[1].time_stamp).count() << std::endl <<
        response[1].camera_position << std::endl;
      center_cnt_ += 1;
      std::cout << "Right Image [" << right_cnt_ << "]: " <<
        convert_airsim_timestamp(response[2].time_stamp).count() << std::endl <<
        response[2].camera_position << std::endl;
      right_cnt_ += 1;
      std::cout << "------------------" << std::endl;
    }
  1. When i move the car around the UE simulator using keyboard the camera positions are not in sync. ideally the x & z position should be in sync for stereo setup. I also tried the pauseSim solution which suggested in other posts but didn't work.

Include full error message in text form

Left Image  [58]: 1637329684254
    1.75
-0.49992
-1.01494
Center Image[58]: 1637329684258
       1.75
7.99627e-05
   -1.01491
Right Image [58]: 1637329684262
    1.75
 0.50008
-1.01488
------------------
Left Image  [59]: 1637329684703
 1.75061
-0.49992
-1.01218
Center Image[59]: 1637329684706
    1.75061
7.98117e-05
   -1.01215
Right Image [59]: 1637329684708
 1.75061
 0.50008
-1.01212
------------------
Left Image  [60]: 1637329685081
  1.69931
-0.497714
 -1.00851
Center Image[60]: 1637329685084
   1.69865
0.00228599
  -1.00848
Right Image [60]: 1637329685086
 1.69799
0.502286
-1.00845
------------------
Left Image  [61]: 1637329685523
   1.2688
-0.498193
 -1.00507
Center Image[61]: 1637329685525
   1.26811
0.00180677
  -1.00504
Right Image [61]: 1637329685527
 1.26742
0.501806
-1.00501
------------------
Left Image  [62]: 1637329685932
 0.472647
-0.499356
 -1.00516
Center Image[62]: 1637329685936
   0.471978
0.000643664
   -1.00513
Right Image [62]: 1637329685939
0.471309
0.500643
 -1.0051

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

@catproof
Copy link

you have simPause commented out

@sguttikon
Copy link
Author

sguttikon commented Nov 19, 2021

@NickPerezCarletonUniversity I know, as I mentioned if i use simPause with ros::AsyncSpinner for > 10Hz fps the UE4 is not responsive to keyboard inputs to control car.

Complete code to reproduce

/**
 *  @file   airsim_ros_node.cpp
 *  @brief  TODO
 *  @author suresh
 *  @date   11.11.2021
 */

// is this to just import rpc ?
#include "common/common_utils/StrictMode.hpp"
STRICT_MODE_OFF
#ifndef RPCLIB_MSGPACK
#define RPCLIB_MSGPACK clmdep_msgpack
#endif  // RPCLIB_MSGPACK
#include "rpc/rpc_error.h"
STRICT_MODE_ON

// c/c++ dependencies
#include <chrono>

// ros dependencies
#include <ros/ros.h>
#include <ros/callback_queue.h>

// airsim dependencies
#include "vehicles/car/api/CarRpcLibClient.hpp"

namespace airsim_ros {

typedef msr::airlib::ImageCaptureBase::ImageRequest ImageRequest;
typedef msr::airlib::ImageCaptureBase::ImageResponse ImageResponse;
typedef msr::airlib::ImageCaptureBase::ImageType ImageType;

class AirSimCar {
 public:

    //  @brief  ros async thread spinners
    ros::AsyncSpinner image_async_spinner_;

    AirSimCar(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private)
        : nh_(nh),
          nh_private_(nh_private),
          image_async_spinner_(1, &image_timer_cb_queue_){

      double update_sim_img_n_sec = 0.1;

      ros::TimerOptions image_timer_options(
        ros::Duration(update_sim_img_n_sec),
        boost::bind(&AirSimCar::image_response_cb, this, _1),
        &image_timer_cb_queue_
      );
      image_response_timer_ = nh_private_.createTimer(image_timer_options);

    }

 private:

    //  @brief  ros node handler
    ros::NodeHandle nh_;
    ros::NodeHandle nh_private_;

    //  @brief  ros timer
    ros::Timer image_response_timer_;

    //  @brief  ros async thread spinners' corresponding callback queue
    ros::CallbackQueue image_timer_cb_queue_;

    //  @brief  airsim's root rpc client
    msr::airlib::CarRpcLibClient airsim_client_;

    //  @brief  counter
    int left_cnt_ = 0;
    int right_cnt_ = 0;
    int center_cnt_ = 0;

    // update left+right images from airsim_client_ every nth sec
    void image_response_cb(const ros::TimerEvent& event) {
      airsim_client_.simPause(true);
      std::vector<ImageRequest> request = {
        ImageRequest("front_left_custom", ImageType::Scene),
        ImageRequest("front_center_custom", ImageType::Scene),
        ImageRequest("front_right_custom", ImageType::Scene)
      };
      const std::vector<ImageResponse>& response = airsim_client_.simGetImages(request);
      airsim_client_.simPause(false);


      std::cout << "Left Image  [" << left_cnt_ << "]: " <<
        convert_airsim_timestamp(response[0].time_stamp).count() << std::endl <<
        response[0].camera_position << std::endl;
      left_cnt_ += 1;
      std::cout << "Center Image[" << center_cnt_ << "]: " <<
        convert_airsim_timestamp(response[1].time_stamp).count() << std::endl <<
        response[1].camera_position << std::endl;
      center_cnt_ += 1;
      std::cout << "Right Image [" << right_cnt_ << "]: " <<
        convert_airsim_timestamp(response[2].time_stamp).count() << std::endl <<
        response[2].camera_position << std::endl;
      right_cnt_ += 1;
      std::cout << "------------------" << std::endl;
    }

    std::chrono::milliseconds convert_airsim_timestamp(const msr::airlib::TTimePoint& stamp) {
      std::chrono::nanoseconds ns(stamp);
      std::chrono::milliseconds ms = std::chrono::duration_cast<std::chrono::milliseconds>(ns);
      return ms;
    }
};

}

int main(int argc, char** argv) {
  ros::init(argc, argv, "airsim_ros_node");
  ros::NodeHandle nh;
  ros::NodeHandle nh_private("~");

  airsim_ros::AirSimCar airsim_car(nh, nh_private);
  airsim_car.image_async_spinner_.start();

  ros::spin();

  return 0;
}

@sguttikon
Copy link
Author

sguttikon commented Nov 19, 2021

Alternative test case, reference hello-car moving car in straight path.

#!/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)
    ])
    client.simPause(False)

    # 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("-----------------------")

output:

Speed -4, Gear -1
Left Image   : 1637359734141319000 <Vector3r> {   'x_val': -12.652186393737793,
    'y_val': -0.49843069911003113,
    'z_val': -1.010461688041687}
Center Image : 1637359734149656000 <Vector3r> {   'x_val': -12.65207290649414,
    'y_val': 0.0015693090390414,
    'z_val': -1.0104314088821411}
Right Image  : 1637359734163097000 <Vector3r> {   'x_val': -12.651957511901855,
    'y_val': 0.5015692710876465,
    'z_val': -1.0104012489318848}
-----------------------    
Speed -5, Gear -1
Left Image   : 1637359580075209000 <Vector3r> {   'x_val': -32.831626892089844,
    'y_val': -0.5001322627067566,
    'z_val': -1.015711784362793}
Center Image : 1637359580081678000 <Vector3r> {   'x_val': -32.83401870727539,
    'y_val': -0.00013793825928587466,
    'z_val': -1.015622615814209}
Right Image  : 1637359580094307000 <Vector3r> {   'x_val': -32.83640670776367,
    'y_val': 0.4998563230037689,
    'z_val': -1.015533447265625}

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

No branches or pull requests

3 participants