Open phil333 opened 4 years ago
So are the images fetched using the Python API same? There's also some discussion on https://github.com/microsoft/AirSim/issues/2369 which might be relevant
Yes, that seems related. Faster image capture or slower clockspeed will solve this to an extend, but they still do not fix the underlying issue that the images are taken at different points in time. In my case the problem is worse because the image resolution is bigger. It seems that the images are captured sequentially.
When working with https://github.com/code-iai/ROSIntegrationVision/ it seemed that each camera was triggered in parallel, and then the readout happened sequentially.
this is a pretty old bug. has anyone found a workaround for this? I am looking to use SLAM in real time. as in, have the stereo camera images fed into the SLAM algorithm and use the estimated state from the SLAM algorithm to control the drone
Did someone able to fix the issue ? I tried pause sim, which some people suggested in other threads, but it didn't work.
Its very annoying, AirSim team didn't provide update on this bug till now. I tried Carla simulator, which is also based on UE, where it is able to sync correctly across multiple images without any issue !!!
code snippet
// 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;
}
output:
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
Settings.json
{
"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}
]
}
@suresh-guttikonda it should work if you pause and un-pause. I tried it that way and it worked. you have simPause commented out, that is probably why it isn't working for you.
yes, i tried with both ways with and without pause/unpause. But still didn't work. Using pause/unpause at 10Hz is making UE4 unresponsive 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;
}
@NickPerezCarletonUniversity could you please tell me are you doing something differently ?? i tried both c++ and python api
@suresh-guttikonda check out this thread: https://github.com/microsoft/AirSim/issues/2369
I'm recording my data, and then performing SLAM on the data afterwards. Instead of controlling the drone manually, I am programming ahead of time (before the simulation starts) where it needs to go, that is why continuously pausing and unpausing the simulation does not give me any issues.
@suresh-guttikonda Have you found a way to get the stereo synchronized images? Until now, with the updated code of the ROS wrapper, I still could not make them synced.
@hoangvietdo I was not able to find any fix and I have moved to alternative Unreal based simulator.
@suresh-guttikonda Thanks for your reply. It seems like they will keep ignoring this old issue until someone makes a PR.
Hi, I am having issues with the ROS interface and the image syncronisation. It seems that the sync issue has been addressed and solved before: https://github.com/microsoft/AirSim/pull/2282
But for some reason this is not the case for the ROS images. (these are also published with a slight delay, but this is less of an issue)
Below are two images taking at the same time by two cameras that have been positioned at the exact same point ins pace:
"Cameras": { "front_left_custom": { "CaptureSettings": [ { "PublishToRos": 1, "ImageType": 0, "Width": 1920, "Height": 1080, "FOV_Degrees": 90, "TargetGamma": 1.8 } ], "X": 1.75, "Y": -0.06, "Z": -1.25, "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0 }, "front_right_custom": { "CaptureSettings": [ { "PublishToRos": 1, "ImageType": 0, "Width": 1920, "Height": 1080, "FOV_Degrees": 90, "TargetGamma": 1.8 } ], "X": 1.75, "Y": 0.06, "Z": -1.25, "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0 } },