Skip to content

Commit 42df687

Browse files
authored
Merge pull request #21 from RoboMaster/develop
Develop
2 parents bc3f06f + 1c5bcdb commit 42df687

File tree

5 files changed

+633
-557
lines changed

5 files changed

+633
-557
lines changed

README.md

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,13 @@
11
# __自主无人机竞速模拟器使用说明__
22
1. ## 更新说明
3+
### v1.1.1
4+
1. 模拟器版本更新 -> v1.1.1; 赛道一, 赛道二添加了视觉标定板, 具体参数参考模拟器根目录README文件; 赛道二动态圈发生碰撞时会停止,防止卡主无人机;
5+
2. roswrapper限制了控制命令的发布频率为100hz;
6+
7+
### v1.1.0-未经稳定性测试,非正式版:
8+
1. 修复imu帧率下降问题;
9+
2. 修复图像时间戳延迟问题;
10+
---
311
### 0830:
412
1. 相机配置文件中的x, y, z 数值 乘以二, 纠正因提及缩放导致的误差;
513
2. FOV由100度改为90度;
@@ -61,7 +69,7 @@
6169
6270
5. ## WIN 端下载并启动模拟器
6371
>在浏览器中输入此网址即可开始下载:
64-
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_WIN.zip`
72+
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_WIN_V1_1_1.zip`
6573
---
6674
>解压后进入文件夹中,参考simulator_WIN.md 启动模拟器
6775
![pic](doc/2022-08-18%2015-26-03%20的屏幕截图.png)
@@ -75,7 +83,7 @@
7583

7684
3. ## LINUX + LINUX 双机开发模式
7785
### 简介
78-
双击模式分离后免除了ros 端程序对模拟器的影响,使得开发更便利。但是 Linux端运行模拟器对帧率有较大的影响。使用 Linux 端 clone此仓库。
86+
双机模式分离后免除了ros 端程序对模拟器的影响,使得开发更便利。但是 Linux端运行模拟器对帧率有较大的影响。使用 Linux 端 clone此仓库。
7987
### 使用说明
8088
1. ## A LINUX 端安装ROS noetic
8189
>设置软件库
@@ -112,7 +120,7 @@
112120
113121
5. ## B LINUX 端下载并启动模拟器
114122
>在浏览器中输入此网址即可开始下载:
115-
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_LINUX.zip`
123+
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_LINUX_V1_1_1.zip`
116124
---
117125
>解压后进入文件夹中,参考simulator_LINUX.md 启动模拟器
118126
![pic](doc/2022-08-18%2015-35-08%20%E7%9A%84%E5%B1%8F%E5%B9%95%E6%88%AA%E5%9B%BE.png)
@@ -163,7 +171,7 @@
163171
164172
5. ## 下载模拟器
165173
>在浏览器中输入此网址即可开始下载:
166-
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_LINUX.zip`
174+
`https://stg-robomasters-hz-q0o2.oss-cn-hangzhou.aliyuncs.com/simulator/simulator_LINUX_V1_1_1.zip`
167175
---
168176
>解压后进入文件夹中,参考simulator_LINUX.md 启动模拟器
169177
![pic](doc/2022-08-18%2015-35-08%20%E7%9A%84%E5%B1%8F%E5%B9%95%E6%88%AA%E5%9B%BE.png)

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

Lines changed: 40 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,7 @@ struct GimbalCmd
135135
// GimbalCmd(const std::string& vehicle_name,
136136
// const std::string& camera_name,
137137
// const msr::airlib::Quaternionr& target_quat) :
138-
// vehicle_name(vehicle_name), camera_name(camera_name), target_quat(target_quat) {};AirsimROSWrapper
138+
// vehicle_name(vehicle_name), camera_name(camera_name), target_quat(target_quat) {};
139139
};
140140

141141
class AirsimROSWrapper
@@ -172,8 +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_;
176-
bool is_used_lidar_timer_cb_queue_;
175+
//ros::AsyncSpinner lidar_async_spinner_;
176+
ros::AsyncSpinner drone_state_async_spinner_;
177+
ros::AsyncSpinner command_listener_async_spinner_;
178+
// ros::AsyncSpinner update_commands_async_spinner_;
179+
// bool is_used_lidar_timer_cb_queue_;
177180
bool is_used_img_timer_cb_queue_;
178181

179182
private:
@@ -262,28 +265,28 @@ class AirsimROSWrapper
262265
void img_response_RGBD_timer_cb(const ros::TimerEvent& event); // update images from airsim_client_ every nth sec
263266
void img_response_stereo_timer_cb(const ros::TimerEvent& event); // update images from airsim_client_ every nth sec
264267
void drone_state_timer_cb(const ros::TimerEvent& event); // update drone state from airsim_client_ every nth sec
265-
void lidar_timer_cb(const ros::TimerEvent& event);
268+
// void lidar_timer_cb(const ros::TimerEvent& event);
266269

267270
/// ROS subscriber callbacks
268271
void pose_cmd_body_frame_cb(const airsim_ros_pkgs::PoseCmd::ConstPtr& msg, const std::string& vehicle_name);
269-
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);
270273
void vel_cmd_body_frame_cb(const airsim_ros_pkgs::VelCmd::ConstPtr& msg, const std::string& vehicle_name);
271274

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

274-
void vel_cmd_group_body_frame_cb(const airsim_ros_pkgs::VelCmdGroup& msg);
275-
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);
276279

277-
void vel_cmd_all_world_frame_cb(const airsim_ros_pkgs::VelCmd& msg);
278-
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);
279282

280283
// void vel_cmd_body_frame_cb(const airsim_ros_pkgs::VelCmd& msg, const std::string& vehicle_name);
281284
void gimbal_angle_quat_cmd_cb(const airsim_ros_pkgs::GimbalAngleQuatCmd& gimbal_angle_quat_cmd_msg);
282285
void gimbal_angle_euler_cmd_cb(const airsim_ros_pkgs::GimbalAngleEulerCmd& gimbal_angle_euler_cmd_msg);
283286

284287
// commands
285288
void car_cmd_cb(const airsim_ros_pkgs::CarControls::ConstPtr& msg, const std::string& vehicle_name);
286-
void update_commands();
289+
// void update_commands(const ros::TimerEvent& event);
287290

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

293296
/// ROS service callbacks
294297
bool takeoff_srv_cb(airsim_ros_pkgs::Takeoff::Request& request, airsim_ros_pkgs::Takeoff::Response& response, const std::string& vehicle_name);
295-
bool takeoff_group_srv_cb(airsim_ros_pkgs::TakeoffGroup::Request& request, airsim_ros_pkgs::TakeoffGroup::Response& response);
296-
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);
297300
bool land_srv_cb(airsim_ros_pkgs::Land::Request& request, airsim_ros_pkgs::Land::Response& response, const std::string& vehicle_name);
298-
bool land_group_srv_cb(airsim_ros_pkgs::LandGroup::Request& request, airsim_ros_pkgs::LandGroup::Response& response);
299-
bool land_all_srv_cb(airsim_ros_pkgs::Land::Request& request, airsim_ros_pkgs::Land::Response& response);
300-
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);
301304

302305
/// ROS tf broadcasters
303-
void publish_camera_tf(const ImageResponse& img_response, const ros::Time& ros_time, const std::string& frame_id, const std::string& child_frame_id);
304-
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);
305308

306309
/// camera helper methods
307310
sensor_msgs::CameraInfo generate_cam_info(const std::string& camera_name, const CameraSetting& camera_setting, const CaptureSetting& capture_setting) const;
@@ -358,16 +361,16 @@ class AirsimROSWrapper
358361
std::string host_ip_;
359362

360363
// subscriber / services for ALL robots
361-
ros::Subscriber vel_cmd_all_body_frame_sub_;
362-
ros::Subscriber vel_cmd_all_world_frame_sub_;
363-
ros::ServiceServer takeoff_all_srvr_;
364-
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_;
365368

366369
// 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
367-
ros::Subscriber vel_cmd_group_body_frame_sub_;
368-
ros::Subscriber vel_cmd_group_world_frame_sub_;
369-
ros::ServiceServer takeoff_group_srvr_;
370-
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_;
371374

372375
AIRSIM_MODE airsim_mode_ = AIRSIM_MODE::DRONE;
373376

@@ -385,15 +388,20 @@ class AirsimROSWrapper
385388
std::unique_ptr<msr::airlib::RpcLibClientBase> airsim_client_ = nullptr;
386389
// seperate busy connections to airsim, update in their own thread
387390
msr::airlib::RpcLibClientBase airsim_client_images_;
388-
msr::airlib::RpcLibClientBase airsim_client_lidar_;
391+
msr::airlib::MultirotorRpcLibClient airsim_client_states_;
392+
// msr::airlib::RpcLibClientBase airsim_client_lidar_;
389393

390394
// 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
391395
// todo for multiple drones with multiple sensors, this won't scale. make it a part of VehicleROS?
392396
ros::CallbackQueue img_timer_cb_queue_;
393397
ros::CallbackQueue img_timer_cb_queue_RGBD_;
394398
ros::CallbackQueue img_timer_cb_queue_stereo_;
395399
ros::CallbackQueue img_timer_cb_queue_bottom_;
396-
ros::CallbackQueue lidar_timer_cb_queue_;
400+
// ros::CallbackQueue lidar_timer_cb_queue_;
401+
ros::CallbackQueue drone_state_timer_cb_queue_;
402+
ros::CallbackQueue command_listener_queue_;
403+
// ros::CallbackQueue default_queue_;
404+
// ros::CallbackQueue update_commands_queue_;
397405

398406
bool img_cb_flag = 0;
399407

@@ -418,14 +426,17 @@ class AirsimROSWrapper
418426

419427
/// ROS params
420428
double vel_cmd_duration_;
421-
429+
430+
long long last_cmd_time;
431+
422432
/// ROS Timers.
423433
ros::Timer airsim_img_response_timer_;
424434
ros::Timer airsim_img_response_bottom_timer_;
425435
ros::Timer airsim_img_response_RGBD_timer_;
426436
ros::Timer airsim_img_response_stereo_timer_;
427437
ros::Timer airsim_control_update_timer_;
428-
ros::Timer airsim_lidar_update_timer_;
438+
// ros::Timer airsim_control_update_timer2_;
439+
// ros::Timer airsim_lidar_update_timer_;
429440

430441
typedef std::pair<std::vector<ImageRequest>, std::string> airsim_img_request_vehicle_name_pair;
431442
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: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,8 @@ int main(int argc, char** argv)
1313
std::string host_ip = "localhost";
1414
nh_private.getParam("host_ip", host_ip);
1515
AirsimROSWrapper airsim_ros_wrapper(nh, nh_private, host_ip);
16-
16+
airsim_ros_wrapper.drone_state_async_spinner_.start();
17+
airsim_ros_wrapper.command_listener_async_spinner_.start();
1718
if (airsim_ros_wrapper.is_used_img_timer_cb_queue_) {
1819
if(airsim_ros_wrapper.is_RGBD_)
1920
{
@@ -28,11 +29,7 @@ int main(int argc, char** argv)
2829
airsim_ros_wrapper.img_bottom_async_spinner_.start();
2930
}
3031

31-
if (airsim_ros_wrapper.is_used_lidar_timer_cb_queue_) {
32-
airsim_ros_wrapper.lidar_async_spinner_.start();
33-
}
34-
35-
ros::spin();
3632

33+
ros::waitForShutdown();
3734
return 0;
3835
}

0 commit comments

Comments
 (0)