Open zdjeffri opened 2 years ago
I'll add, that in ROS terms at least, the airsim_node is not acting as a clock server when "use_sim_time" is true, but when "use_sim_time" is false, it is acting as a clock server. It should work in both cases, given "publish_clock" is set to true in the launchfile. Hopefully, this clarifies the issue.
Hello, I also had an issue using ROS wrapper regarding simulated clock. I was recording all data into a rosbag. To be able to record simulated data and clock while using a custom ClockSpeed I did the following:
Renamed clock topic from /airsim_node/clock
to /clock
. To do this, I replaced NodeHandle nh_private_
to nh_
in airsim_ros_wrapper.cpp:319
:
clock_pub_ = nh_.advertise<rosgraph_msgs::Clock>("/clock", 1);
Do not forget to build the plugin after doing this modification.
Launch airsim_node using following command:
roslaunch airsim_ros_pkgs airsim_node.launch publish_clock:=true
Record topic in a bag after setting /use_sim_time
param to true
in the same terminal:
rosparam set use_sim_time true
rosbag record /airsim_node/Drone1/front_left_custom/Scene /tf /tf_static -O airsim.bag
This way, my rosbag is recorded using published clock.
When I play the rosbag file without any specific option everything works well
rosbag play airsim.bag
You can also check your bag file using:
rosbag info --freq airsim.bag
@yhabib29 What version of AirSim are you using? Are you using a car or a drone? What version of ROS? This solution did not work. AirSim, whether using public or private nodehandle, only publishes clock if use_sim_time is false - which is my problem. If use_sim_time is true, clock is not published.
Hey @zdjeffri , sorry again, I have just checked the whole pipeline and I was wrong in my second comment (removed). I edited my first comment again with the correct procedure ! Let me know if it works for you.
Any updates to airsim_ros that addresses this issue? the above method works for recording bag files but does not enable testing navigation algorithms in simulation (i.e. SIL). Can force ROS to use real-time but then if Airsim clock speed is != 1.0, there are timing issues.
I recently meet the same problem and solve it by changing the timer of drone_state_timer_cb from ros::Timer to ros::WallTimer.
The issue seems to be that AirSim's ROS wrapper publishes /airsim_node/clock
based on ros::Timer
, which when use_sim_time=true
only runs if /clock
is advancing. So it's a chicken-egg problem.
// airsim_ros_wrapper.h
ros::Timer airsim_control_update_timer_;
// airsim_ros_wrapper.cpp
airsim_control_update_timer_ = nh_private_.createTimer(
ros::Duration(update_airsim_control_every_n_sec),
&AirsimROSWrapper::drone_state_timer_cb, this);
void AirsimROSWrapper::drone_state_timer_cb(const ros::WallTimerEvent& event)
{
// other stuff
// publish the simulation clock
if (publish_clock_) {
clock_pub_.publish(ros_clock_);
}
// other stuff
}
@dylanyd's ros::WallTimer
solution is a valid workaround that makes airsim_control_update_timer_
advance from the system clock instead of ROS' /clock
topic. However a fully correct solution would be to somehow sync to AirSim/Unreal Engine's internal clock. That way setting AirSim's clockspeed will also synchronize here. Not sure how to do that yet. Will update when that's figured out.
Bug report
What's the issue you encountered?
Using AirSim to simulate lidar data for an autonomous robot. Have the clock speed for AirSim set at 0.5 (via settings.json). Can confirm this works properly because the clock topic is running at half-speed when the "use_sim_time" rosparam is false. However, if "use_sim_time" is set to true, the clock is no longer published and the ROS Wrapper ceases to publish anything. In order to properly integrate the AirSim clock with other ROS nodes, "use_sim_time" needs to be set to true so that the ROS Time API returns what is being published by AirSim instead of the system clock.
Settings and other relevant files
AirSim Settings - settings.json roslaunch file - airsim_node.launch
How can the issue be reproduced?
roslaunch airsim_ros_pkgs airsim_node.launch output:=screen host:=$WSL_HOST_IP