Skip to content

Commit f14cc9c

Browse files
committed
0909:修复图像延迟问题,修复imu频率受控制命令影响的问题;非稳定版本
1 parent fd8b636 commit f14cc9c

File tree

5 files changed

+499
-484
lines changed

5 files changed

+499
-484
lines changed

README.md

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,8 @@
11
# __自主无人机竞速模拟器使用说明__
22
1. ## 更新说明
3-
### 0907:
4-
1. 修复imu帧率下降,未经稳定性测试,非正式版;
3+
### 0909-未经稳定性测试,非正式版:
4+
1. 修复imu帧率下降问题;
5+
2. 修复图像时间戳延迟问题;
56
---
67
### 0830:
78
1. 相机配置文件中的x, y, z 数值 乘以二, 纠正因提及缩放导致的误差;
@@ -64,7 +65,7 @@
6465
6566
5. ## WIN 端下载并启动模拟器
6667
>在浏览器中输入此网址即可开始下载:
67-
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_WIN.zip`
68+
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_WIN_0909.zip`
6869
---
6970
>解压后进入文件夹中,参考simulator_WIN.md 启动模拟器
7071
![pic](doc/2022-08-18%2015-26-03%20的屏幕截图.png)

roswrapper/ros/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h

Lines changed: 30 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -172,11 +172,11 @@ class AirsimROSWrapper
172172
ros::AsyncSpinner img_RGBD_async_spinner_;
173173
ros::AsyncSpinner img_stereo_async_spinner_;
174174
ros::AsyncSpinner img_bottom_async_spinner_;
175-
ros::AsyncSpinner lidar_async_spinner_;
175+
//ros::AsyncSpinner lidar_async_spinner_;
176176
ros::AsyncSpinner drone_state_async_spinner_;
177177
ros::AsyncSpinner command_listener_async_spinner_;
178-
ros::AsyncSpinner update_commands_async_spinner_;
179-
bool is_used_lidar_timer_cb_queue_;
178+
// ros::AsyncSpinner update_commands_async_spinner_;
179+
// bool is_used_lidar_timer_cb_queue_;
180180
bool is_used_img_timer_cb_queue_;
181181

182182
private:
@@ -265,28 +265,28 @@ class AirsimROSWrapper
265265
void img_response_RGBD_timer_cb(const ros::TimerEvent& event); // update images from airsim_client_ every nth sec
266266
void img_response_stereo_timer_cb(const ros::TimerEvent& event); // update images from airsim_client_ every nth sec
267267
void drone_state_timer_cb(const ros::TimerEvent& event); // update drone state from airsim_client_ every nth sec
268-
void lidar_timer_cb(const ros::TimerEvent& event);
268+
// void lidar_timer_cb(const ros::TimerEvent& event);
269269

270270
/// ROS subscriber callbacks
271271
void pose_cmd_body_frame_cb(const airsim_ros_pkgs::PoseCmd::ConstPtr& msg, const std::string& vehicle_name);
272-
void vel_cmd_world_frame_cb(const airsim_ros_pkgs::VelCmd::ConstPtr& msg, const std::string& vehicle_name);
272+
// void vel_cmd_world_frame_cb(const airsim_ros_pkgs::VelCmd::ConstPtr& msg, const std::string& vehicle_name);
273273
void vel_cmd_body_frame_cb(const airsim_ros_pkgs::VelCmd::ConstPtr& msg, const std::string& vehicle_name);
274274

275275
void angle_rate_throttle_frame_cb(const airsim_ros_pkgs::AngleRateThrottle::ConstPtr& msg, const std::string& vehicle_name);
276276

277-
void vel_cmd_group_body_frame_cb(const airsim_ros_pkgs::VelCmdGroup& msg);
278-
void vel_cmd_group_world_frame_cb(const airsim_ros_pkgs::VelCmdGroup& msg);
277+
// void vel_cmd_group_body_frame_cb(const airsim_ros_pkgs::VelCmdGroup& msg);
278+
// void vel_cmd_group_world_frame_cb(const airsim_ros_pkgs::VelCmdGroup& msg);
279279

280-
void vel_cmd_all_world_frame_cb(const airsim_ros_pkgs::VelCmd& msg);
281-
void vel_cmd_all_body_frame_cb(const airsim_ros_pkgs::VelCmd& msg);
280+
// void vel_cmd_all_world_frame_cb(const airsim_ros_pkgs::VelCmd& msg);
281+
// void vel_cmd_all_body_frame_cb(const airsim_ros_pkgs::VelCmd& msg);
282282

283283
// void vel_cmd_body_frame_cb(const airsim_ros_pkgs::VelCmd& msg, const std::string& vehicle_name);
284284
void gimbal_angle_quat_cmd_cb(const airsim_ros_pkgs::GimbalAngleQuatCmd& gimbal_angle_quat_cmd_msg);
285285
void gimbal_angle_euler_cmd_cb(const airsim_ros_pkgs::GimbalAngleEulerCmd& gimbal_angle_euler_cmd_msg);
286286

287287
// commands
288288
void car_cmd_cb(const airsim_ros_pkgs::CarControls::ConstPtr& msg, const std::string& vehicle_name);
289-
void update_commands(const ros::TimerEvent& event);
289+
// void update_commands(const ros::TimerEvent& event);
290290

291291
// state, returns the simulation timestamp best guess based on drone state timestamp, airsim needs to return timestap for environment
292292
ros::Time update_state();
@@ -295,16 +295,16 @@ class AirsimROSWrapper
295295

296296
/// ROS service callbacks
297297
bool takeoff_srv_cb(airsim_ros_pkgs::Takeoff::Request& request, airsim_ros_pkgs::Takeoff::Response& response, const std::string& vehicle_name);
298-
bool takeoff_group_srv_cb(airsim_ros_pkgs::TakeoffGroup::Request& request, airsim_ros_pkgs::TakeoffGroup::Response& response);
299-
bool takeoff_all_srv_cb(airsim_ros_pkgs::Takeoff::Request& request, airsim_ros_pkgs::Takeoff::Response& response);
298+
// bool takeoff_group_srv_cb(airsim_ros_pkgs::TakeoffGroup::Request& request, airsim_ros_pkgs::TakeoffGroup::Response& response);
299+
// bool takeoff_all_srv_cb(airsim_ros_pkgs::Takeoff::Request& request, airsim_ros_pkgs::Takeoff::Response& response);
300300
bool land_srv_cb(airsim_ros_pkgs::Land::Request& request, airsim_ros_pkgs::Land::Response& response, const std::string& vehicle_name);
301-
bool land_group_srv_cb(airsim_ros_pkgs::LandGroup::Request& request, airsim_ros_pkgs::LandGroup::Response& response);
302-
bool land_all_srv_cb(airsim_ros_pkgs::Land::Request& request, airsim_ros_pkgs::Land::Response& response);
303-
bool reset_srv_cb(airsim_ros_pkgs::Reset::Request& request, airsim_ros_pkgs::Reset::Response& response);
301+
// bool land_group_srv_cb(airsim_ros_pkgs::LandGroup::Request& request, airsim_ros_pkgs::LandGroup::Response& response);
302+
// bool land_all_srv_cb(airsim_ros_pkgs::Land::Request& request, airsim_ros_pkgs::Land::Response& response);
303+
// bool reset_srv_cb(airsim_ros_pkgs::Reset::Request& request, airsim_ros_pkgs::Reset::Response& response);
304304

305305
/// ROS tf broadcasters
306-
void publish_camera_tf(const ImageResponse& img_response, const ros::Time& ros_time, const std::string& frame_id, const std::string& child_frame_id);
307-
void publish_odom_tf(const nav_msgs::Odometry& odom_msg);
306+
// void publish_camera_tf(const ImageResponse& img_response, const ros::Time& ros_time, const std::string& frame_id, const std::string& child_frame_id);
307+
// void publish_odom_tf(const nav_msgs::Odometry& odom_msg);
308308

309309
/// camera helper methods
310310
sensor_msgs::CameraInfo generate_cam_info(const std::string& camera_name, const CameraSetting& camera_setting, const CaptureSetting& capture_setting) const;
@@ -361,16 +361,16 @@ class AirsimROSWrapper
361361
std::string host_ip_;
362362

363363
// subscriber / services for ALL robots
364-
ros::Subscriber vel_cmd_all_body_frame_sub_;
365-
ros::Subscriber vel_cmd_all_world_frame_sub_;
366-
ros::ServiceServer takeoff_all_srvr_;
367-
ros::ServiceServer land_all_srvr_;
364+
// ros::Subscriber vel_cmd_all_body_frame_sub_;
365+
// ros::Subscriber vel_cmd_all_world_frame_sub_;
366+
// ros::ServiceServer takeoff_all_srvr_;
367+
// ros::ServiceServer land_all_srvr_;
368368

369369
// todo - subscriber / services for a GROUP of robots, which is defined by a list of `vehicle_name`s passed in the ros msg / srv request
370-
ros::Subscriber vel_cmd_group_body_frame_sub_;
371-
ros::Subscriber vel_cmd_group_world_frame_sub_;
372-
ros::ServiceServer takeoff_group_srvr_;
373-
ros::ServiceServer land_group_srvr_;
370+
// ros::Subscriber vel_cmd_group_body_frame_sub_;
371+
// ros::Subscriber vel_cmd_group_world_frame_sub_;
372+
// ros::ServiceServer takeoff_group_srvr_;
373+
// ros::ServiceServer land_group_srvr_;
374374

375375
AIRSIM_MODE airsim_mode_ = AIRSIM_MODE::DRONE;
376376

@@ -389,19 +389,19 @@ class AirsimROSWrapper
389389
// seperate busy connections to airsim, update in their own thread
390390
msr::airlib::RpcLibClientBase airsim_client_images_;
391391
msr::airlib::MultirotorRpcLibClient airsim_client_states_;
392-
msr::airlib::RpcLibClientBase airsim_client_lidar_;
392+
// msr::airlib::RpcLibClientBase airsim_client_lidar_;
393393

394394
// todo not sure if async spinners shuold be inside this class, or should be instantiated in airsim_node.cpp, and cb queues should be public
395395
// todo for multiple drones with multiple sensors, this won't scale. make it a part of VehicleROS?
396396
ros::CallbackQueue img_timer_cb_queue_;
397397
ros::CallbackQueue img_timer_cb_queue_RGBD_;
398398
ros::CallbackQueue img_timer_cb_queue_stereo_;
399399
ros::CallbackQueue img_timer_cb_queue_bottom_;
400-
ros::CallbackQueue lidar_timer_cb_queue_;
400+
// ros::CallbackQueue lidar_timer_cb_queue_;
401401
ros::CallbackQueue drone_state_timer_cb_queue_;
402402
ros::CallbackQueue command_listener_queue_;
403403
// ros::CallbackQueue default_queue_;
404-
ros::CallbackQueue update_commands_queue_;
404+
// ros::CallbackQueue update_commands_queue_;
405405

406406
bool img_cb_flag = 0;
407407

@@ -433,8 +433,8 @@ class AirsimROSWrapper
433433
ros::Timer airsim_img_response_RGBD_timer_;
434434
ros::Timer airsim_img_response_stereo_timer_;
435435
ros::Timer airsim_control_update_timer_;
436-
ros::Timer airsim_control_update_timer2_;
437-
ros::Timer airsim_lidar_update_timer_;
436+
// ros::Timer airsim_control_update_timer2_;
437+
// ros::Timer airsim_lidar_update_timer_;
438438

439439
typedef std::pair<std::vector<ImageRequest>, std::string> airsim_img_request_vehicle_name_pair;
440440
std::vector<airsim_img_request_vehicle_name_pair> airsim_img_request_vehicle_name_pair_vec_;

roswrapper/ros/src/airsim_ros_pkgs/launch/airsim_node.launch

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -47,13 +47,13 @@
4747
<node name="airsim_node" pkg="airsim_ros_pkgs" type="airsim_node" output="$(arg output)">
4848
<param name="is_vulkan" type="bool" value="false" />
4949
<!-- ROS timer rates. Note that timer callback will be processed at maximum possible rate, upperbounded by the following ROS params -->
50-
<param name="update_airsim_img_response_every_n_sec" type="double" value="0.05" />
50+
<param name="update_airsim_img_response_every_n_sec" type="double" value="0.050" />
5151
<param name="update_airsim_control_every_n_sec" type="double" value="0.01" />
52-
<param name="update_lidar_every_n_sec" type="double" value="0.01" />
52+
<param name="update_lidar_every_n_sec" type="double" value="1" />
5353
<param name="publish_clock" type="bool" value="$(arg publish_clock)" />
5454
<param name="host_ip" type="string" value="$(arg host_ip)" />
5555
</node>
5656

5757
<!-- Static transforms -->
58-
<!-- include file="$(find airsim_ros_pkgs)/launch/static_transforms.launch"/-->
58+
<!--include file="$(find airsim_ros_pkgs)/launch/static_transforms.launch"/-->
5959
</launch>

roswrapper/ros/src/airsim_ros_pkgs/src/airsim_node.cpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@ int main(int argc, char** argv)
1414
nh_private.getParam("host_ip", host_ip);
1515
AirsimROSWrapper airsim_ros_wrapper(nh, nh_private, host_ip);
1616
airsim_ros_wrapper.drone_state_async_spinner_.start();
17-
airsim_ros_wrapper.update_commands_async_spinner_.start();
1817
airsim_ros_wrapper.command_listener_async_spinner_.start();
1918
if (airsim_ros_wrapper.is_used_img_timer_cb_queue_) {
2019
if(airsim_ros_wrapper.is_RGBD_)
@@ -30,9 +29,6 @@ int main(int argc, char** argv)
3029
airsim_ros_wrapper.img_bottom_async_spinner_.start();
3130
}
3231

33-
if (airsim_ros_wrapper.is_used_lidar_timer_cb_queue_) {
34-
airsim_ros_wrapper.lidar_async_spinner_.start();
35-
}
3632

3733
ros::waitForShutdown();
3834
return 0;

0 commit comments

Comments
 (0)