From cb7df9f8e69fd71c2c34acf8e8e81dda2650e21c Mon Sep 17 00:00:00 2001 From: EasonHua <1628280289@qq.com> Date: Mon, 20 May 2024 15:21:54 +0800 Subject: [PATCH 1/3] [update | v2.1.0] Merge `PointCloud2` from several sources, with `frame_id = "base_link"` --- README.md | 20 ++-------- launch/mapping.launch | 27 +------------ launch/tf_transform.launch | 23 ------------ launch/uav_octomapping.launch | 71 ----------------------------------- src/merge_pcl/pcl_merge.cpp | 10 ++--- 5 files changed, 11 insertions(+), 140 deletions(-) delete mode 100644 launch/tf_transform.launch delete mode 100644 launch/uav_octomapping.launch diff --git a/README.md b/README.md index 683dcb5..a55861c 100644 --- a/README.md +++ b/README.md @@ -9,10 +9,11 @@ A ROS package for mapping with LiDAR and D435i, modified from [global_planning]( ![Static Badge](https://img.shields.io/badge/Ubuntu-18.04.6-E95420?logo=ubuntu) ![Static Badge](https://img.shields.io/badge/NVIDIA-Jetson_Nano-76B900?LOGO=nvidia) + ## Release Note - v2.1.1: Publish pose -- v2.1.0: Merge `PointCloud2` from several sources, with frame_id = "map" +- v2.1.0: Merge `PointCloud2` from several sources, with `frame_id = "base_link"` > RealSense T265 is a tracking camera that is designed to be more optimal for Visual Odometry and SLAM (wider field of view and not using infrared light). It can do SLAM onboard as well as loop closure. However, this camera is not able to return RGB images (since it does not have a RGB camera onboard) and the depth returned is not as good as the D400 series (and can be a little trickier to get). @@ -57,7 +58,6 @@ rosrun octomap_server octomap_saver -f map.bt ![image](Log/2024-03-11/%E6%97%A0%E6%A0%87%E9%A2%98.png) - 参考: - https://octomap.github.io/octomap/doc - ⭐️ https://wiki.ros.org/octomap @@ -73,9 +73,6 @@ rosrun octomap_server octomap_saver -f map.bt ```bash rosrun rviz rviz -``` - -```bash rosrun octomap_server octomap_server_node map.bt ``` @@ -118,18 +115,9 @@ roslaunch cartographer_ros ~/cartographer_ws/src/cartographer_ros/cartographer_r ```bash rosservice call /finish_trajectory 0 -``` - -```bash rosservice call /write_state "{filename: '~/map.pbstream'}" ``` -由于板载计算机性能较差,因此只开展了仿真实验。 - -```bash -roslaunch cartographer_ros demo_backpack_3d.launch bag_filename:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag -``` - ![image](https://github.com/HuaYuXiao/UAV-Dynamic-Obstacle-Avoidance/assets/117464811/fb10c834-d753-452b-b0a5-3b5b0b7bae20) 参考: @@ -144,7 +132,7 @@ roslaunch cartographer_ros demo_backpack_3d.launch bag_filename:=${HOME}/Downloa @@ -152,7 +140,7 @@ sudo apt-get install ros-melodic-rtabmap-ros roslaunch realsense2_camera rs_rtabmap.launch ``` -**2024年2月28日更新**:`rtabmap`涉及到RGB-D,该机器不具备直接获取深度数据的能力,因此该方案废弃。 +`rtabmap`涉及到RGB-D 参考: - [Introduction to Intel® RealSense™ Visual SLAM and the T265 Tracking Camera](https://dev.intelrealsense.com/docs/intel-realsensetm-visual-slam-and-the-t265-tracking-camera) diff --git a/launch/mapping.launch b/launch/mapping.launch index 47b66f4..2361532 100644 --- a/launch/mapping.launch +++ b/launch/mapping.launch @@ -4,33 +4,13 @@ - - - - - - - - - - - - - - - - - - + @@ -76,8 +56,5 @@ - - - - + diff --git a/launch/tf_transform.launch b/launch/tf_transform.launch deleted file mode 100644 index f33a7b4..0000000 --- a/launch/tf_transform.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/launch/uav_octomapping.launch b/launch/uav_octomapping.launch deleted file mode 100644 index 884edd4..0000000 --- a/launch/uav_octomapping.launch +++ /dev/null @@ -1,71 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/merge_pcl/pcl_merge.cpp b/src/merge_pcl/pcl_merge.cpp index 27cfecc..9323645 100644 --- a/src/merge_pcl/pcl_merge.cpp +++ b/src/merge_pcl/pcl_merge.cpp @@ -31,8 +31,8 @@ PointCloudMerger::PointCloudMerger() : nh_("~"){ LiDAR_pcl.reset(new pcl::PointCloud()); D435i_pcl.reset(new pcl::PointCloud()); - listener_LiDAR.waitForTransform("map", "3Dlidar_link", ros::Time(0), ros::Duration(0.05)); - listener_D435i.waitForTransform("map", "D435i::camera_depth_frame", ros::Time(0), ros::Duration(0.05)); + listener_LiDAR.waitForTransform("base_link", "3Dlidar_link", ros::Time(0), ros::Duration(0.05)); + listener_D435i.waitForTransform("base_link", "D435i::camera_depth_frame", ros::Time(0), ros::Duration(0.05)); // 设置cout的精度为小数点后两位 std::cout << std::fixed << std::setprecision(2); @@ -45,7 +45,7 @@ void PointCloudMerger::LiDAR_cb(const sensor_msgs::PointCloud2ConstPtr& msg) { pcl::fromROSMsg(*msg, *LiDAR_pcl); // 转换LiDAR点云到map坐标系 - pcl_ros::transformPointCloud("map", *LiDAR_pcl, *LiDAR_pcl, listener_LiDAR); + pcl_ros::transformPointCloud("base_link", *LiDAR_pcl, *LiDAR_pcl, listener_LiDAR); mergePointClouds(); } @@ -55,7 +55,7 @@ void PointCloudMerger::D435i_cb(const sensor_msgs::PointCloud2ConstPtr& msg) { pcl::fromROSMsg(*msg, *D435i_pcl); // 转换D435i点云到map坐标系 - pcl_ros::transformPointCloud("map", *D435i_pcl, *D435i_pcl, listener_D435i); + pcl_ros::transformPointCloud("base_link", *D435i_pcl, *D435i_pcl, listener_D435i); mergePointClouds(); } @@ -66,7 +66,7 @@ void PointCloudMerger::mergePointClouds() { merged_pcl->header.seq = LiDAR_pcl->header.seq; merged_pcl->header.stamp = LiDAR_pcl->header.stamp; - merged_pcl->header.frame_id = "map"; + merged_pcl->header.frame_id = "base_link"; *merged_pcl += *LiDAR_pcl; *merged_pcl += *D435i_pcl; From 18be145cba701b6b268f899724fc8680939dea55 Mon Sep 17 00:00:00 2001 From: EasonHua <1628280289@qq.com> Date: Thu, 23 May 2024 22:54:10 +0800 Subject: [PATCH 2/3] [update | update | v2.1.2] import `message_filters::sync_policies::ApproximateTime` for merge --- README.md | 13 +++--- include/merge_pcl/merge_pcl.h | 4 ++ package.xml | 5 +-- src/merge_pcl/pcl_merge.cpp | 77 ++++++++++++++++------------------- 4 files changed, 47 insertions(+), 52 deletions(-) diff --git a/README.md b/README.md index a55861c..ed18025 100644 --- a/README.md +++ b/README.md @@ -10,15 +10,16 @@ A ROS package for mapping with LiDAR and D435i, modified from [global_planning]( ![Static Badge](https://img.shields.io/badge/NVIDIA-Jetson_Nano-76B900?LOGO=nvidia) -## Release Note +> RealSense T265 is a tracking camera that is designed to be more optimal for Visual Odometry and SLAM (wider field of view and not using infrared light). It can do SLAM onboard as well as loop closure. However, this camera is not able to return RGB images (since it does not have a RGB camera onboard) and the depth returned is not as good as the D400 series (and can be a little trickier to get). -- v2.1.1: Publish pose -- v2.1.0: Merge `PointCloud2` from several sources, with `frame_id = "base_link"` +> Using both a RealSense D435i sensor and a RealSense T265 sensor can provide both the maps and the better quality visual odometry for developing a full SLAM system. The D435i used for the mapping, and the T265 for the tracking. -> RealSense T265 is a tracking camera that is designed to be more optimal for Visual Odometry and SLAM (wider field of view and not using infrared light). It can do SLAM onboard as well as loop closure. However, this camera is not able to return RGB images (since it does not have a RGB camera onboard) and the depth returned is not as good as the D400 series (and can be a little trickier to get). +## Release Note -> Using both a RealSense D435i sensor and a RealSense T265 sensor can provide both the maps and the better quality visual odometry for developing a full SLAM system. The D435i used for the mapping, and the T265 for the tracking. +- v2.1.2: import `message_filters::sync_policies::ApproximateTime` for merge +- v2.1.1: publish pose +- v2.1.0: merge `PointCloud2` from several sources, with `frame_id = "base_link"` ## Installation @@ -35,7 +36,7 @@ catkin_make install --source src/uav_octomapping --build build/uav_octomapping In real world, ```bash -roslaunch uav_octomapping uav_octomapping.launch +roslaunch uav_octomapping experiment.launch ``` In simulator, diff --git a/include/merge_pcl/merge_pcl.h b/include/merge_pcl/merge_pcl.h index 1565479..3d4ec17 100644 --- a/include/merge_pcl/merge_pcl.h +++ b/include/merge_pcl/merge_pcl.h @@ -17,5 +17,9 @@ #include #include #include +#include +#include +#include +#include #endif //UAV_OCTOMAPPING_ADD_PCL_H diff --git a/package.xml b/package.xml index 2a3fee9..75ea5b0 100644 --- a/package.xml +++ b/package.xml @@ -1,12 +1,12 @@ uav_octomapping - 2.1.1 + 2.1.2 A ROS package for mapping with LiDAR and D435i Eason Yi - Eason Hua + Eason Hua Apache https://amovlab.com @@ -25,7 +25,6 @@ tf - catkin diff --git a/src/merge_pcl/pcl_merge.cpp b/src/merge_pcl/pcl_merge.cpp index 9323645..e5c1245 100644 --- a/src/merge_pcl/pcl_merge.cpp +++ b/src/merge_pcl/pcl_merge.cpp @@ -2,34 +2,35 @@ using namespace std; -namespace message_filters { - template - class Subscriber; -} - class PointCloudMerger { public: PointCloudMerger(); - void LiDAR_cb(const sensor_msgs::PointCloud2ConstPtr& msg); - void D435i_cb(const sensor_msgs::PointCloud2ConstPtr& msg); - void mergePointClouds(); + ~PointCloudMerger() = default; + + void mergeCallback(const sensor_msgs::PointCloud2ConstPtr& depth, + const sensor_msgs::PointCloud2ConstPtr& scan); private: + typedef message_filters::sync_policies::ApproximateTime + SyncPolicy; + typedef shared_ptr> Synchronizer; + ros::NodeHandle nh_; - ros::Subscriber LiDAR_sub, D435i_sub; + shared_ptr> LiDAR_sub_, D435i_sub_; + Synchronizer synchronizer_; tf::TransformListener listener_LiDAR, listener_D435i; ros::Publisher merged_pub_; - pcl::PointCloud::Ptr LiDAR_pcl, D435i_pcl; tf::StampedTransform transform_LiDAR, transform_D435i; }; PointCloudMerger::PointCloudMerger() : nh_("~"){ - LiDAR_sub = nh_.subscribe("/prometheus/sensors/3Dlidar_scan", 1, &PointCloudMerger::LiDAR_cb, this); - D435i_sub = nh_.subscribe("/camera/depth/color/points", 1, &PointCloudMerger::D435i_cb, this); - merged_pub_ = nh_.advertise("/prometheus/merged_pcl", 1); + LiDAR_sub_.reset(new message_filters::Subscriber(nh_, "/prometheus/sensors/3Dlidar_scan", 50)); + D435i_sub_.reset(new message_filters::Subscriber(nh_, "/camera/depth/color/points", 50)); - LiDAR_pcl.reset(new pcl::PointCloud()); - D435i_pcl.reset(new pcl::PointCloud()); + synchronizer_.reset(new message_filters::Synchronizer(SyncPolicy(100), *LiDAR_sub_, *D435i_sub_)); + synchronizer_->registerCallback(boost::bind(&PointCloudMerger::mergeCallback, this, _1, _2)); + + merged_pub_ = nh_.advertise("/prometheus/merged_pcl", 10); listener_LiDAR.waitForTransform("base_link", "3Dlidar_link", ros::Time(0), ros::Duration(0.05)); listener_D435i.waitForTransform("base_link", "D435i::camera_depth_frame", ros::Time(0), ros::Duration(0.05)); @@ -40,43 +41,33 @@ PointCloudMerger::PointCloudMerger() : nh_("~"){ std::cout << "[mapping] merge_pcl initialized!" << std::endl; } -void PointCloudMerger::LiDAR_cb(const sensor_msgs::PointCloud2ConstPtr& msg) { - cout << "[merge_pcl] LiDAR received!" << endl; - - pcl::fromROSMsg(*msg, *LiDAR_pcl); - // 转换LiDAR点云到map坐标系 - pcl_ros::transformPointCloud("base_link", *LiDAR_pcl, *LiDAR_pcl, listener_LiDAR); - - mergePointClouds(); -} - -void PointCloudMerger::D435i_cb(const sensor_msgs::PointCloud2ConstPtr& msg) { - cout << "[merge_pcl] D435i received!" << endl; +void PointCloudMerger::mergeCallback(const sensor_msgs::PointCloud2ConstPtr& depth, + const sensor_msgs::PointCloud2ConstPtr& scan) { + pcl::PointCloud::Ptr D435i_pcl, LiDAR_pcl, merged_pcl; - pcl::fromROSMsg(*msg, *D435i_pcl); + D435i_pcl.reset(new pcl::PointCloud()); + pcl::fromROSMsg(*depth, *D435i_pcl); // 转换D435i点云到map坐标系 pcl_ros::transformPointCloud("base_link", *D435i_pcl, *D435i_pcl, listener_D435i); - - mergePointClouds(); -} -void PointCloudMerger::mergePointClouds() { - pcl::PointCloud::Ptr merged_pcl; - merged_pcl.reset(new pcl::PointCloud()); + LiDAR_pcl.reset(new pcl::PointCloud()); + pcl::fromROSMsg(*scan, *LiDAR_pcl); + // 转换LiDAR点云到map坐标系 + pcl_ros::transformPointCloud("base_link", *LiDAR_pcl, *LiDAR_pcl, listener_LiDAR); - merged_pcl->header.seq = LiDAR_pcl->header.seq; - merged_pcl->header.stamp = LiDAR_pcl->header.stamp; - merged_pcl->header.frame_id = "base_link"; + merged_pcl.reset(new pcl::PointCloud()); - *merged_pcl += *LiDAR_pcl; - *merged_pcl += *D435i_pcl; + merged_pcl->header.seq = LiDAR_pcl->header.seq; + merged_pcl->header.stamp = LiDAR_pcl->header.stamp; + merged_pcl->header.frame_id = "base_link"; - sensor_msgs::PointCloud2 merged_cloud_msg; - pcl::toROSMsg(*merged_pcl, merged_cloud_msg); + *merged_pcl += *LiDAR_pcl; + *merged_pcl += *D435i_pcl; - merged_pub_.publish(merged_cloud_msg); + sensor_msgs::PointCloud2 merged_cloud_msg; + pcl::toROSMsg(*merged_pcl, merged_cloud_msg); - cout << "Merged pcl published!" << endl; + merged_pub_.publish(merged_cloud_msg); } int main(int argc, char** argv) { From b37839e4fbf450b84ae49b2c2c7156dff5c9e156 Mon Sep 17 00:00:00 2001 From: EasonHua <1628280289@qq.com> Date: Thu, 23 May 2024 22:54:20 +0800 Subject: [PATCH 3/3] [update | update | v2.1.2] --- config/merge_pcl.rviz | 364 ------------------------------------ config/px4_config.yaml | 262 -------------------------- config/px4_pluginlists.yaml | 33 ---- config/px4_sender.yaml | 20 -- config/rviz_config.rviz | 344 ++++++++++++++++++++-------------- launch/simulation.launch | 14 +- rosgraph.dot | 290 ---------------------------- 7 files changed, 213 insertions(+), 1114 deletions(-) delete mode 100644 config/merge_pcl.rviz delete mode 100644 config/px4_config.yaml delete mode 100644 config/px4_pluginlists.yaml delete mode 100644 config/px4_sender.yaml delete mode 100644 rosgraph.dot diff --git a/config/merge_pcl.rviz b/config/merge_pcl.rviz deleted file mode 100644 index 9cb45a5..0000000 --- a/config/merge_pcl.rviz +++ /dev/null @@ -1,364 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 0 - Name: Displays - Property Tree Widget: - Expanded: - - /TF1/Frames1 - Splitter Ratio: 0.43611112236976624 - Tree Height: 443 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Nav Goal1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Name: Time - SyncMode: 0 - SyncSource: Image_color -Preferences: - PromptSaveOnExit: false -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 1000 - Reference Frame: - Value: true - - Class: rviz/TF - Enabled: true - Filter (blacklist): "" - Filter (whitelist): "" - Frame Timeout: 15 - Frames: - 3Dlidar_link: - Value: true - All Enabled: false - D435i::camera_depth_frame: - Value: true - base_link: - Value: true - base_link_frd: - Value: false - camera_link: - Value: true - map: - Value: true - map_ned: - Value: false - odom: - Value: true - odom_ned: - Value: false - world: - Value: true - Marker Alpha: 1 - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: true - Tree: - world: - base_link: - 3Dlidar_link: - {} - base_link_frd: - {} - camera_link: - D435i::camera_depth_frame: - {} - map: - map_ned: - {} - odom: - odom_ned: - {} - Update Interval: 0 - Value: true - - Class: rviz/Group - Displays: - - Alpha: 1 - Axes Length: 0.20000000298023224 - Axes Radius: 0.019999999552965164 - Class: rviz/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.10000000149011612 - Name: Drone_Pose - Queue Size: 10 - Shaft Length: 1 - Shaft Radius: 0.05000000074505806 - Shape: Axes - Topic: /mavros/local_position/pose - Unreliable: false - Value: true - - Alpha: 1 - Buffer Length: 30 - Class: rviz/Path - Color: 255; 25; 0 - Enabled: true - Head Diameter: 0.30000001192092896 - Head Length: 0.20000000298023224 - Length: 0.30000001192092896 - Line Style: Billboards - Line Width: 0.05000000074505806 - Name: Drone_Path - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 255; 85; 255 - Pose Style: None - Queue Size: 10 - Radius: 0.029999999329447746 - Shaft Diameter: 0.10000000149011612 - Shaft Length: 0.10000000149011612 - Topic: /prometheus/drone_trajectory - Unreliable: false - Value: true - - Alpha: 1 - Axes Length: 0.20000000298023224 - Axes Radius: 0.019999999552965164 - Class: rviz/Pose - Color: 255; 25; 0 - Enabled: true - Head Length: 0.30000001192092896 - Head Radius: 0.10000000149011612 - Name: Reference_Pose - Queue Size: 10 - Shaft Length: 1 - Shaft Radius: 0.05000000074505806 - Shape: Axes - Topic: /prometheus/control/ref_pose_rviz - Unreliable: false - Value: true - Enabled: true - Name: 无人机状态 - - Alpha: 0.5 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 2.610640048980713 - Min Value: -0.13460394740104675 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: LaserScan - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Flat Squares - Topic: /prometheus/sensors/3Dlidar_scan - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Group - Displays: - - Class: rviz/Image - Enabled: true - Image Topic: /camera/color/image_raw - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image_color - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /camera/depth/image_raw - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image_depth - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - Enabled: true - Name: Image - - Class: rviz/Group - Displays: - - Alpha: 0.5 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 3 - Min Value: 0.009999999776482582 - Value: false - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 85; 170; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: octomap - Position Transformer: XYZ - Queue Size: 1 - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Boxes - Topic: /octomap_point_cloud_centers - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Alpha: 0.5 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 2.2299046516418457 - Min Value: -0.28734925389289856 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: AxisColor - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: depth_map - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Flat Squares - Topic: /camera/depth/color/points - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: merged_pcl - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Flat Squares - Topic: /prometheus/merged_pcl - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - Enabled: true - Name: Mapping - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: world - Frame Rate: 60 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/Measure - - Class: rviz/SetGoal - Topic: /prometheus/planning/goal - Value: true - Views: - Current: - Class: rviz/Orbit - Distance: 16.41176414489746 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Field of View: 0.7853981852531433 - Focal Point: - X: 0.005263702943921089 - Y: 1.3101428747177124 - Z: 1.6219030618667603 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.9000001549720764 - Target Frame: world - Yaw: 1.6349998712539673 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1254 - Hide Left Dock: false - Hide Right Dock: false - Image_color: - collapsed: false - Image_depth: - collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000001940000048cfc0200000026fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730200000780000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001f8000000c900fffffffb0000000a00560069006500770073000000041c0000018b000000a400fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006100000001d1000000b50000000000000000fb0000000a0049006d00610067006502000001a2000001e1000000f8000000b5fb0000000a006400650070007400680000000155000002310000000000000000fb0000000a0049006d0061006700650100000415000000f80000000000000000fb0000000a0049006d00610067006501000003f4000001190000000000000000fb0000000a0064006500700074006800000004a2000000ac0000000000000000fb0000000a0064006500700074006800000003b4000001b60000000000000000fb0000000a0064006500700074006800000004b9000000950000000000000000fb0000000a006400650070007400680000000481000000cd0000000000000000fb0000000a006400650070007400680000000429000001250000000000000000fb0000000a0064006500700074006800000003b7000000af0000000000000000fb0000000a0064006500700074006800000003d5000000b50000000000000000fb0000000a006400650070007400680000000444000001260000000000000000fb0000000a00640065007000740068000000041f0000014b0000000000000000fb0000000a0064006500700074006800000001b8000000160000000000000000fb0000000a0064006500700074006800000001c1000000160000000000000000fb0000000a0064006500700074006800000004b1000000550000000000000000fb0000000a006400650070007400680000000505000000650000000000000000fb0000000a006400650070007400680000000502000000680000000000000000fb0000000a0064006500700074006800000004f9000000710000000000000000fb0000000a0064006500700074006800000004e9000000810000000000000000fb0000000a0064006500700074006800000004de0000008c0000000000000000fb0000000a0064006500700074006800000004cc0000009e0000000000000000fb0000000a0064006500700074006800000004bb000000af0000000000000000fb0000000a0064006500700074006800000004aa000000c00000000000000000fb0000000a006400650070007400680000000498000000d20000000000000000fb0000000a0049006d00610067006500000003fa000001540000000000000000fb000000160049006d006100670065005f0063006f006c006f0072010000023b000001450000001600fffffffb000000160049006d006100670065005f006400650070007400680100000386000001430000001600ffffff000000010000010f00000385fc0200000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006100000003bfc0100000002fb0000000800540069006d00650000000000000006100000041800fffffffb0000000800540069006d00650100000000000004500000000000000000000006800000048c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 2074 - X: 806 - Y: 509 diff --git a/config/px4_config.yaml b/config/px4_config.yaml deleted file mode 100644 index c55d898..0000000 --- a/config/px4_config.yaml +++ /dev/null @@ -1,262 +0,0 @@ -# Common configuration for PX4 autopilot -# -# node: -startup_px4_usb_quirk: true - -# --- system plugins --- - -# sys_status & sys_time connection options -conn: - heartbeat_rate: 1.0 # send hertbeat rate in Hertz - timeout: 10.0 # hertbeat timeout in seconds - timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0) - system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0) - -# sys_status -sys: - min_voltage: 10.0 # diagnostics min voltage - disable_diag: false # disable all sys_status diagnostics, except heartbeat - -# sys_time -time: - time_ref_source: "fcu" # time_reference source - timesync_mode: MAVLINK - timesync_avg_alpha: 0.6 # timesync averaging factor - -# --- mavros plugins (alphabetical order) --- - -# 3dr_radio -tdr_radio: - low_rssi: 40 # raw rssi lower level for diagnostics - -# actuator_control -# None - -# command -cmd: - use_comp_id_system_control: false # quirk for some old FCUs - -# dummy -# None - -# ftp -# None - -# global_position -global_position: - frame_id: "map" # origin frame - child_frame_id: "base_link" # body-fixed frame - rot_covariance: 99999.0 # covariance for attitude? - gps_uere: 1.0 # User Equivalent Range Error (UERE) of GPS sensor (m) - use_relative_alt: true # use relative altitude for local coordinates - tf: - send: false # send TF? - frame_id: "map" # TF frame_id - global_frame_id: "earth" # TF earth frame_id - child_frame_id: "base_link" # TF child_frame_id - -# imu_pub -imu: - frame_id: "base_link" - # need find actual values - linear_acceleration_stdev: 0.0003 - angular_velocity_stdev: 0.0003490659 // 0.02 degrees - orientation_stdev: 1.0 - magnetic_stdev: 0.0 - -# local_position -local_position: - frame_id: "world" - tf: - send: true - frame_id: "world" - child_frame_id: "base_link" - send_fcu: false - -# param -# None, used for FCU params - -# rc_io -# None - -# safety_area -safety_area: - p1: {x: 1.0, y: 1.0, z: 1.0} - p2: {x: -1.0, y: -1.0, z: -1.0} - -# setpoint_accel -setpoint_accel: - send_force: false - -# setpoint_attitude -setpoint_attitude: - reverse_thrust: false # allow reversed thrust - use_quaternion: false # enable PoseStamped topic subscriber - tf: - listen: false # enable tf listener (disable topic subscribers) - frame_id: "map" - child_frame_id: "target_attitude" - rate_limit: 50.0 - -setpoint_raw: - thrust_scaling: 1.0 # used in setpoint_raw attitude callback. - # Note: PX4 expects normalized thrust values between 0 and 1, which means that - # the scaling needs to be unitary and the inputs should be 0..1 as well. - -# setpoint_position -setpoint_position: - tf: - listen: false # enable tf listener (disable topic subscribers) - frame_id: "map" - child_frame_id: "target_position" - rate_limit: 50.0 - mav_frame: LOCAL_NED - -# setpoint_velocity -setpoint_velocity: - mav_frame: LOCAL_NED - -# vfr_hud -# None - -# waypoint -mission: - pull_after_gcs: true # update mission if gcs updates - use_mission_item_int: true # use the MISSION_ITEM_INT message instead of MISSION_ITEM - # for uploading waypoints to FCU - -# --- mavros extras plugins (same order) --- - -# adsb -# None - -# debug_value -# None - -# distance_sensor -## Currently available orientations: -# Check http://wiki.ros.org/mavros/Enumerations -## -distance_sensor: - hrlv_ez4_pub: - id: 0 - frame_id: "hrlv_ez4_sonar" - orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facing - field_of_view: 0.0 # XXX TODO - send_tf: true - sensor_position: {x: 0.0, y: 0.0, z: -0.1} - lidarlite_pub: - id: 1 - frame_id: "lidarlite_laser" - orientation: PITCH_270 - field_of_view: 0.0 # XXX TODO - send_tf: true - sensor_position: {x: 0.0, y: 0.0, z: -0.1} - sonar_1_sub: - subscriber: true - id: 2 - orientation: PITCH_270 - laser_1_sub: - subscriber: true - id: 3 - orientation: PITCH_270 - -# image_pub -image: - frame_id: "px4flow" - -# fake_gps -fake_gps: - # select data source - use_mocap: true # ~mocap/pose - mocap_transform: true # ~mocap/tf instead of pose - use_vision: false # ~vision (pose) - # origin (default: Zürich) - geo_origin: - lat: 47.3667 # latitude [degrees] - lon: 8.5500 # longitude [degrees] - alt: 408.0 # altitude (height over the WGS-84 ellipsoid) [meters] - eph: 2.0 - epv: 2.0 - satellites_visible: 5 # virtual number of visible satellites - fix_type: 3 # type of GPS fix (default: 3D) - tf: - listen: false - send: false # send TF? - frame_id: "map" # TF frame_id - child_frame_id: "fix" # TF child_frame_id - rate_limit: 10.0 # TF rate - gps_rate: 5.0 # GPS data publishing rate - -# landing_target -landing_target: - listen_lt: false - mav_frame: "LOCAL_NED" - land_target_type: "VISION_FIDUCIAL" - image: - width: 640 # [pixels] - height: 480 - camera: - fov_x: 2.0071286398 # default: 115 [degrees] - fov_y: 2.0071286398 - tf: - send: true - listen: false - frame_id: "landing_target" - child_frame_id: "camera_center" - rate_limit: 10.0 - target_size: {x: 0.3, y: 0.3} - -# mocap_pose_estimate -mocap: - # select mocap source - use_tf: false # ~mocap/tf - use_pose: true # ~mocap/pose - -# odom -odometry: - fcu: - odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry - odom_child_id_des: "base_link" # desired child frame rotation of the FCU's odometry - -# px4flow -px4flow: - frame_id: "px4flow" - ranger_fov: 0.118682 # 6.8 degrees at 5 meters, 31 degrees at 1 meter - ranger_min_range: 0.3 # meters - ranger_max_range: 5.0 # meters - -# vision_pose_estimate -vision_pose: - tf: - listen: false # enable tf listener (disable topic subscribers) - frame_id: "odom" - child_frame_id: "vision_estimate" - rate_limit: 10.0 - -# vision_speed_estimate -vision_speed: - listen_twist: true # enable listen to twist topic, else listen to vec3d topic - twist_cov: true # enable listen to twist with covariance topic - -# vibration -vibration: - frame_id: "base_link" - -# wheel_odometry -wheel_odometry: - count: 2 # number of wheels to compute odometry - use_rpm: false # use wheel's RPM instead of cumulative distance to compute odometry - wheel0: {x: 0.0, y: -0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m) - wheel1: {x: 0.0, y: 0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m) - send_raw: true # send wheel's RPM and cumulative distance (~/wheel_odometry/rpm, ~/wheel_odometry/distance) - send_twist: false # send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry - frame_id: "odom" # origin frame - child_frame_id: "base_link" # body-fixed frame - vel_error: 0.1 # wheel velocity measurement error 1-std (m/s) - tf: - send: false - frame_id: "odom" - child_frame_id: "base_link" - -# vim:set ts=2 sw=2 et: diff --git a/config/px4_pluginlists.yaml b/config/px4_pluginlists.yaml deleted file mode 100644 index 145d262..0000000 --- a/config/px4_pluginlists.yaml +++ /dev/null @@ -1,33 +0,0 @@ -plugin_blacklist: -- actuator_control -- adsb -- safety_area -- 3dr_radio -- cam_imu_sync -- altitude -- distance_sensor -- fake_gps -- gps_rtk -- hil -- home_position -- landing_target -- mocap_pose_estimate -- mount_control -- obstacle_distance -- rc_io -- vfr_hud -- waypoint -- wind_estimation -- px4flow -- global_position -- companion_process_status -- debug_value -- wheel_odometry -- vibration -- odom -- setpoint_attitude -- setpoint_position -- setpoint_accel -- setpoint_velocity -plugin_whitelist: [] -#- 'sys_*' \ No newline at end of file diff --git a/config/px4_sender.yaml b/config/px4_sender.yaml deleted file mode 100644 index 0c28778..0000000 --- a/config/px4_sender.yaml +++ /dev/null @@ -1,20 +0,0 @@ -## parameter for px4_sender.cpp - -## 起飞高度,建议设置小一点 -## 2020.11.04测试发现飞机起飞有较大超调,未发现原因,但起飞后控制正常 -Takeoff_height : 0.4 -## 降落速度 -Land_speed : 0.2 -## 上锁高度 -Disarm_height : 0.18 -## 降落模式选择 -Land_mode : 1 - -## 地理围栏,根据实际情况设置 -geo_fence: - x_min: -2.0 - x_max: 6.0 - y_min: -2.0 - y_max: 6.0 - z_min: -0.5 - z_max: 3.0 diff --git a/config/rviz_config.rviz b/config/rviz_config.rviz index 7175a9c..deba027 100644 --- a/config/rviz_config.rviz +++ b/config/rviz_config.rviz @@ -1,20 +1,18 @@ Panels: - Class: rviz/Displays - Help Height: 78 + Help Height: 0 Name: Displays Property Tree Widget: Expanded: - /TF1/Frames1 - /无人机状态1 - - /无人机状态1/Drone_Pose1 - - /规划路径1 - Splitter Ratio: 0.37542086839675903 - Tree Height: 363 + - /Mapping1 + Splitter Ratio: 0.43611112236976624 + Tree Height: 769 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties - Expanded: - - /3D Nav Goal1 + Expanded: ~ Name: Tool Properties Splitter Ratio: 0.5886790156364441 - Class: rviz/Views @@ -23,20 +21,13 @@ Panels: Name: Views Splitter Ratio: 0.5 - Class: rviz/Time - Experimental: false Name: Time SyncMode: 0 - SyncSource: 激光雷达数据 - - + SyncSource: Image_color Preferences: PromptSaveOnExit: false - - Toolbars: toolButtonStyle: 2 - - Visualization Manager: Class: "" Displays: @@ -55,63 +46,59 @@ Visualization Manager: Y: 0 Z: 0 Plane: XY - Plane Cell Count: 20 - Reference Frame: + Plane Cell Count: 16 + Reference Frame: world Value: true - Class: rviz/TF Enabled: true + Filter (blacklist): "" + Filter (whitelist): "" Frame Timeout: 15 Frames: + 3Dlidar_link: + Value: true All Enabled: false + D435i::camera_depth_frame: + Value: true + D435i::camera_link: + Value: true + D435i::imu_link: + Value: true base_link: - Value: false - base_link_frd: Value: true - lidar_link: + base_link_frd: Value: false map: - Value: false - map_ned: Value: true + map_ned: + Value: false odom: Value: true odom_ned: - Value: true - t265_accel_frame: - Value: false - t265_accel_optical_frame: - Value: false - t265_gyro_frame: - Value: false - t265_gyro_optical_frame: - Value: false - t265_link: - Value: false - t265_odom_frame: - Value: false - t265_pose_frame: Value: false world: - Value: false + Value: true + Marker Alpha: 1 Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: true Tree: + odom: + odom_ned: + {} world: base_link: - base_link_frd: + 3Dlidar_link: {} - lidar_link: + D435i::camera_link: + D435i::camera_depth_frame: + {} + D435i::imu_link: + {} + base_link_frd: {} - t265_link: - t265_accel_frame: - t265_accel_optical_frame: - {} - t265_gyro_frame: - t265_gyro_optical_frame: - {} map: map_ned: {} @@ -120,21 +107,21 @@ Visualization Manager: - Class: rviz/Group Displays: - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.10000000149011612 + Axes Length: 0.20000000298023224 + Axes Radius: 0.019999999552965164 Class: rviz/Pose Color: 255; 25; 0 Enabled: true Head Length: 0.30000001192092896 Head Radius: 0.10000000149011612 Name: Drone_Pose + Queue Size: 10 Shaft Length: 1 Shaft Radius: 0.05000000074505806 Shape: Axes Topic: /mavros/local_position/pose Unreliable: false Value: true - - Alpha: 1 Buffer Length: 30 Class: rviz/Path @@ -144,7 +131,7 @@ Visualization Manager: Head Length: 0.20000000298023224 Length: 0.30000001192092896 Line Style: Billboards - Line Width: 0.029999999329447746 + Line Width: 0.05000000074505806 Name: Drone_Path Offset: X: 0 @@ -152,22 +139,23 @@ Visualization Manager: Z: 0 Pose Color: 255; 85; 255 Pose Style: None + Queue Size: 10 Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 Topic: /prometheus/drone_trajectory Unreliable: false Value: true - - Alpha: 1 - Axes Length: 0.5 - Axes Radius: 0.15000000596046448 + Axes Length: 0.20000000298023224 + Axes Radius: 0.019999999552965164 Class: rviz/Pose Color: 255; 25; 0 Enabled: true Head Length: 0.30000001192092896 Head Radius: 0.10000000149011612 Name: Reference_Pose + Queue Size: 10 Shaft Length: 1 Shaft Radius: 0.05000000074505806 Shape: Axes @@ -175,81 +163,154 @@ Visualization Manager: Unreliable: false Value: true Enabled: true - Name: Drone_state - - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/LaserScan - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: LaserScan - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /prometheus/sensors/2Dlidar_scan - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - - Class: octomap_rviz_plugin/OccupancyGrid + Name: 无人机状态 + - Class: rviz/Group + Displays: + - Alpha: 0.5 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 3 + Min Value: 0.009999999776482582 + Value: false + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 85; 170; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: octomap + Position Transformer: XYZ + Queue Size: 1 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /octomap_point_cloud_centers + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.5 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 2.6109619140625 + Min Value: -0.30847617983818054 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 0; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 0; 0 + Min Color: 255; 0; 0 + Name: merged_pcl + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /prometheus/merged_pcl + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.5 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 2.2299046516418457 + Min Value: -0.28734925389289856 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: depth_map + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /camera/depth/color/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 0.5 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 2.610640048980713 + Min Value: -0.13460394740104675 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: AxisColor + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /prometheus/sensors/3Dlidar_scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false Enabled: true - Max. Height Display: 3.4028234663852886e+38 - Max. Octree Depth: 16 - Min. Height Display: -3.4028234663852886e+38 - Name: OccupancyGrid - Octomap Topic: /octomap_binary - Queue Size: 5 - Value: true - Voxel Alpha: 1 - Voxel Coloring: Z-Axis - Voxel Rendering: Occupied Voxels - - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: FlatColor - Decay Time: 0 + Name: Mapping + - Class: rviz/Group + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /camera/color/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image_color + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /camera/depth/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image_depth + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: false Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.019999999552965164 - Style: Flat Squares - Topic: /octomap_point_cloud_centers - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - + Name: Image Enabled: true Global Options: - Background Color: 48; 48; 48 + Background Color: 255; 253; 224 Default Light: true Fixed Frame: world Frame Rate: 60 @@ -257,40 +318,41 @@ Visualization Manager: Tools: - Class: rviz/Interact Hide Inactive Objects: true - Value: true Views: Current: Class: rviz/Orbit - Distance: 7.276445388793945 + Distance: 16.41176414489746 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false + Field of View: 0.7853981852531433 Focal Point: - X: -0.6879035830497742 - Y: -0.159935861825943 - Z: 1.8105119466781616 + X: 0.005263702943921089 + Y: 1.3101428747177124 + Z: 1.6219030618667603 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 1.5547962188720703 - Target Frame: - Value: Orbit (rviz) - Yaw: 3.098813533782959 + Pitch: 0.9000001549720764 + Target Frame: world + Yaw: 1.5707999467849731 Saved: ~ - - Window Geometry: Displays: - collapsed: true - Height: 696 + collapsed: false + Height: 1254 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000025400000260fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000002700000260000000c900fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007300000002500000012f0000005c00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000342fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000342000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004bf0000003efc0100000002fb0000000800540069006d00650100000000000004bf000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004bf0000023000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Image_color: + collapsed: false + Image_depth: + collapsed: false + QMainWindow State: 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 Selection: collapsed: false Time: @@ -299,6 +361,6 @@ Window Geometry: collapsed: false Views: collapsed: false - Width: 640 - X: 640 - Y: 24 + Width: 2074 + X: 806 + Y: 509 diff --git a/launch/simulation.launch b/launch/simulation.launch index be16d4e..f9b6c10 100644 --- a/launch/simulation.launch +++ b/launch/simulation.launch @@ -1,15 +1,21 @@ + + + - + - + + + - + + - + diff --git a/rosgraph.dot b/rosgraph.dot deleted file mode 100644 index dbe613f..0000000 --- a/rosgraph.dot +++ /dev/null @@ -1,290 +0,0 @@ -digraph graphname { - graph [bb="0,0,2253.7,556.6", - compound=True, - rank=same, - rankdir=LR, - ranksep=0.2 - ]; - node [label="\N"]; - subgraph cluster___t265 { - graph [bb="8,185.6,740.76,308.6", - compound=True, - label="/t265", - lheight=0.21, - lp="374.38,297.1", - lwidth=0.39, - rank=same, - rankdir=LR, - ranksep=0.2, - style=bold - ]; - n___t265__realsense2_camera [URL=__t265__realsense2_camera, - height=0.5, - label="/t265/realsense2_camera", - pos="114.14,218.6", - shape=ellipse, - tooltip="/t265/realsense2_camera", - width=2.7261]; - n___t265__realsense2_camera -> n___t265__realsense2_camera [URL=topic_3A__t265__realsense2_camera_manager__bond, - label="/t265/realsense2_camera_manager/bond", - lp="114.14,262.1", - penwidth=1, - pos="e,133.2,236.38 95.086,236.38 91.848,245.92 98.2,254.6 114.14,254.6 123.86,254.6 130.01,251.38 132.6,246.7"]; - n___t265__realsense2_camera_manager [URL=__t265__realsense2_camera_manager, - height=0.5, - label="/t265/realsense2_camera_manager", - pos="599.52,219.6", - shape=ellipse, - tooltip="/t265/realsense2_camera_manager", - width=3.7011]; - n___t265__realsense2_camera -> n___t265__realsense2_camera_manager [URL=topic_3A__t265__realsense2_camera_manager__bond, - label="/t265/realsense2_camera_manager/bond", - lp="339.28,226.1", - penwidth=1, - pos="e,466.03,219.33 212.37,218.8 282.22,218.95 377.18,219.14 455.58,219.3"]; - n___t265__realsense2_camera_manager -> n___t265__realsense2_camera [URL=topic_3A__t265__realsense2_camera_manager__bond, - label="/t265/realsense2_camera_manager/bond", - lp="339.28,250.1", - penwidth=1, - pos="e,181.8,231.66 506.31,232.52 487.47,234.64 467.77,236.5 449.28,237.6 351.68,243.43 326.73,245.59 229.28,237.6 217.09,236.6 204.25,235.02 191.74,233.18"]; - n___t265__realsense2_camera_manager -> n___t265__realsense2_camera_manager [URL=topic_3A__t265__realsense2_camera_manager__bond, - label="/t265/realsense2_camera_manager/bond", - lp="599.52,263.1", - penwidth=1, - pos="e,624.69,237.38 574.35,237.38 570.08,246.92 578.47,255.6 599.52,255.6 612.35,255.6 620.48,252.38 623.9,247.7"]; - } - subgraph cluster___prometheus_control { - graph [bb="769.76,67.601,1917.4,142.6", - compound=True, - label="/prometheus_control", - lheight=0.21, - lp="1343.6,131.1", - lwidth=1.57, - rank=same, - rankdir=LR, - ranksep=0.2, - style=bold - ]; - n___prometheus_control__px4_sender [URL=__prometheus_control__px4_sender, - height=0.5, - label="/prometheus_control/px4_sender", - pos="1782.7,93.601", - shape=ellipse, - tooltip="/prometheus_control/px4_sender", - width=3.5205]; - n___prometheus_control__px4_pos_estimator [URL=__prometheus_control__px4_pos_estimator, - height=0.5, - label="/prometheus_control/px4_pos_estimator", - pos="931.15,93.601", - shape=ellipse, - tooltip="/prometheus_control/px4_pos_estimator", - width=4.2607]; - n___prometheus_control__px4_pos_estimator -> n___prometheus_control__px4_sender [URL=topic_3A__prometheus__drone_state, - label="/prometheus/drone_state", - lp="1370.7,101.1", - penwidth=1, - pos="e,1655.8,93.601 1084.9,93.601 1244.5,93.601 1492.1,93.601 1645.4,93.601"]; - } - n___t265__realsense2_camera_manager -> n___prometheus_control__px4_pos_estimator [URL=topic_3A__tf, - label="/tf", - lp="755.26,109.1", - penwidth=1, - pos="e,866.45,77.247 708.55,209.23 720.79,203.96 731.98,196.66 740.76,186.6 753.23,172.31 735.01,114.68 748.76,101.6 776.68,75.045 819.21,71.907 856.18,75.934"]; - n___mavros [URL=__mavros, - height=0.5, - label="/mavros", - pos="1370.7,185.6", - shape=ellipse, - tooltip="/mavros", - width=1.1013]; - n___t265__realsense2_camera_manager -> n___mavros [URL=topic_3A__tf, - label="/tf", - lp="931.15,221.1", - penwidth=1, - pos="e,1331.7,188.92 729.95,215.85 866.9,211.58 1088.5,203.72 1279.5,192.6 1293.2,191.81 1308,190.76 1321.6,189.71"]; - n___octomap_server [URL=__octomap_server, - height=0.5, - label="/octomap_server", - pos="1782.7,370.6", - shape=ellipse, - tooltip="/octomap_server", - width=1.9318]; - n___t265__realsense2_camera_manager -> n___octomap_server [URL=topic_3A__tf, - label="/tf", - lp="1186,373.1", - penwidth=1, - pos="e,1713,370.39 643.15,236.69 674.59,251.13 715.73,274.73 740.76,307.6 748.34,317.56 738.86,326.94 748.76,334.6 786.28,363.65 1466.6,369.27 1702.7,370.35"]; - n___ground_station_msg [URL=__ground_station_msg, - height=0.5, - label="/ground_station_msg", - pos="2168.5,54.601", - shape=ellipse, - tooltip="/ground_station_msg", - width=2.3651]; - n___prometheus_control__px4_sender -> n___ground_station_msg [URL=topic_3A__prometheus__message__main, - label="/prometheus/message/main", - lp="2000.4,87.101", - penwidth=1, - pos="e,2091.5,62.389 1886.1,83.15 1947,76.988 2023.3,69.277 2081.3,63.423"]; - n___prometheus_control__px4_sender -> n___mavros [URL=topic_3A__mavros__setpoint_raw__attitude, - label="/mavros/setpoint_raw/attitude", - lp="1554.9,122.1", - penwidth=1, - pos="e,1405.5,176.94 1660.2,98.286 1573,102.16 1469.7,108.08 1461.9,114.6 1450.7,124 1463.2,135.28 1453.9,146.6 1444,158.71 1429.4,167.27 1415.2,173.22"]; - n___ground_station [URL=__ground_station, - height=0.5, - label="/ground_station", - pos="2168.5,131.6", - shape=ellipse, - tooltip="/ground_station", - width=1.8234]; - n___prometheus_control__px4_sender -> n___ground_station [URL=topic_3A__prometheus__log__control, - label="/prometheus/log/control", - lp="2000.4,130.1", - penwidth=1, - pos="e,2106.7,125.52 1886.8,103.86 1953.3,110.41 2037.7,118.72 2096.8,124.53"]; - n___prometheus_control__px4_pos_estimator -> n___ground_station_msg [URL=topic_3A__prometheus__message__main, - label="/prometheus/message/main", - lp="1554.9,10.101", - penwidth=1, - pos="e,2099.8,43.904 986.96,76.831 1056.6,56.871 1179.6,24.718 1287.5,12.601 1582.1,-20.448 1934.8,20.486 2089.4,42.424"]; - n___prometheus_control__px4_pos_estimator -> n___mavros [URL=topic_3A__mavros__vision_pose__pose, - label="/mavros/vision_pose/pose", - lp="1186,164.1", - penwidth=1, - pos="e,1339.9,174.22 990.93,110.25 1021.2,118.2 1058.6,127.34 1092.5,133.6 1174.9,148.81 1197.7,138.73 1279.5,156.6 1296.3,160.27 1314.4,165.7 1330,170.88"]; - n___tf_2Dlidar [URL=__tf_2Dlidar, - height=0.5, - label="/tf_2Dlidar", - pos="599.52,334.6", - shape=ellipse, - tooltip="/tf_2Dlidar", - width=1.3902]; - n___tf_2Dlidar -> n___prometheus_control__px4_pos_estimator [URL=topic_3A__tf, - label="/tf", - lp="755.26,236.1", - penwidth=1, - pos="e,836.34,107.77 646.57,340.76 677.78,342.01 717.19,337.62 740.76,312.6 753.62,298.95 745.53,247.07 748.76,228.6 755.23,191.54 744.06,174.07 769.76,146.6 785.12,130.19 805.63,118.85 826.88,111.02"]; - n___tf_2Dlidar -> n___mavros [URL=topic_3A__tf, - label="/tf", - lp="931.15,276.1", - penwidth=1, - pos="e,1338.1,195.85 647.5,340.06 678.1,340.75 716.44,336.01 740.76,312.6 754.14,299.73 735.13,284.21 748.76,271.6 750.12,270.34 1277.7,210.95 1279.5,210.6 1295.7,207.48 1313.1,202.98 1328.4,198.66"]; - n___tf_2Dlidar -> n___octomap_server [URL=topic_3A__tf, - label="/tf", - lp="1186,395.1", - penwidth=1, - pos="e,1715,374.95 640.03,345.3 669.85,352.61 711.52,361.67 748.76,365.6 1104.3,403.18 1532.4,385.32 1705,375.53"]; - n___mavros -> n___prometheus_control__px4_sender [URL=topic_3A__mavros__setpoint_raw__target_local, - label="/mavros/setpoint_raw/target_local", - lp="1554.9,164.1", - penwidth=1, - pos="e,1733.6,110.31 1401.6,174.22 1419.1,168.17 1441.5,161.08 1461.9,156.6 1543.3,138.79 1566.4,150.62 1647.9,133.6 1673.1,128.34 1700.4,120.63 1723.8,113.38"]; - n___mavros -> n___prometheus_control__px4_pos_estimator [URL=topic_3A__mavros__imu__data, - label="/mavros/imu/data", - lp="1186,126.1", - penwidth=1, - pos="e,1082.8,96.515 1336.2,176.76 1319.3,170.81 1300,161.3 1287.5,146.6 1279.1,136.75 1289.6,126.76 1279.5,118.6 1264.4,106.32 1176.7,100.07 1093,96.888"]; - n___mavros -> n___mavros [URL=topic_3A__tf, - label="/tf", - lp="1370.7,229.1", - penwidth=1, - pos="e,1399.5,198.52 1341.9,198.52 1328.8,209.74 1338.4,221.6 1370.7,221.6 1395,221.6 1406.4,214.93 1405.1,206.86"]; - n___mavros -> n___ground_station [URL=topic_3A__mavros__setpoint_raw__target_local, - label="/mavros/setpoint_raw/target_local", - lp="1782.7,179.1", - penwidth=1, - pos="e,2107.4,138.49 1410.5,183.85 1517.9,178.96 1822.7,164.03 2075.4,141.6 2082.5,140.97 2090,140.26 2097.4,139.52"]; - n___mavros -> n___octomap_server [URL=topic_3A__tf, - label="/tf", - lp="1554.9,292.1", - penwidth=1, - pos="e,1759.3,353.36 1404.6,195 1457.8,210.37 1563.7,243.35 1647.9,284.6 1684.9,302.7 1724.2,328.68 1750.8,347.34"]; - n___tf_world_map [URL=__tf_world_map, - height=0.5, - label="/tf_world_map", - pos="599.52,159.6", - shape=ellipse, - tooltip="/tf_world_map", - width=1.7693]; - n___tf_world_map -> n___prometheus_control__px4_pos_estimator [URL=topic_3A__tf, - label="/tf", - lp="755.26,71.101", - penwidth=1, - pos="e,889.21,76.218 618.44,142.21 645.13,118.98 696.44,78.975 748.76,63.601 792,50.895 842.69,61.16 879.64,73.016"]; - n___tf_world_map -> n___mavros [URL=topic_3A__tf, - label="/tf", - lp="931.15,184.1", - penwidth=1, - pos="e,1331,184.26 662.96,161.74 812.73,166.79 1185.8,179.37 1320.9,183.92"]; - n___tf_world_map -> n___octomap_server [URL=topic_3A__tf, - label="/tf", - lp="1186,348.1", - penwidth=1, - pos="e,1714.7,366.69 659.03,153 687.85,153.3 720.51,159.43 740.76,181.6 759.53,202.15 729.06,286.94 748.76,306.6 752.99,310.83 1464.7,352.26 1704.7,366.11"]; - n___terminal_control [URL=__terminal_control, - height=0.5, - label="/terminal_control", - pos="1370.7,39.601", - shape=ellipse, - tooltip="/terminal_control", - width=2.004]; - n___terminal_control -> n___prometheus_control__px4_sender [URL=topic_3A__prometheus__control_command, - label="/prometheus/control_command", - lp="1554.9,81.101", - penwidth=1, - pos="e,1696.1,80.421 1436.3,47.172 1492.5,53.774 1575.6,63.802 1647.9,73.601 1660.2,75.268 1673.1,77.092 1685.9,78.938"]; - n___tf_t265 [URL=__tf_t265, - height=0.5, - label="/tf_t265", - pos="599.52,435.6", - shape=ellipse, - tooltip="/tf_t265", - width=1.0652]; - n___tf_t265 -> n___prometheus_control__px4_pos_estimator [URL=topic_3A__tf, - label="/tf", - lp="755.26,354.1", - penwidth=1, - pos="e,829.96,107.28 633.43,427.13 666.18,417.12 714.56,397.14 740.76,361.6 771.33,320.13 755.05,298.68 761.76,247.6 763.23,236.44 762.8,155.45 769.76,146.6 782.74,130.09 800.99,118.66 820.57,110.77"]; - n___tf_t265 -> n___mavros [URL=topic_3A__tf, - label="/tf", - lp="931.15,446.1", - penwidth=1, - pos="e,1369.6,203.73 637.93,436.46 773.89,439.19 1227,445.42 1279.5,408.6 1344.3,363.19 1363.2,263.11 1368.6,213.96"]; - n___tf_t265 -> n___octomap_server [URL=topic_3A__tf, - label="/tf", - lp="1186,549.1", - penwidth=1, - pos="e,1764.3,388.01 622.63,450.12 654.36,469.11 713.86,501.4 769.76,513.6 1066.9,578.44 1151.3,528.23 1453.9,497.6 1540.8,488.81 1567.1,499.7 1647.9,466.6 1689.6,449.51 1730.9,417.27 1756.5,394.9"]; - n___laser_to_pointcloud [URL=__laser_to_pointcloud, - height=0.5, - label="/laser_to_pointcloud", - pos="1370.7,470.6", - shape=ellipse, - tooltip="/laser_to_pointcloud", - width=2.3109]; - n___laser_to_pointcloud -> n___octomap_server [URL=topic_3A__prometheus__sensors__pcl2, - label="/prometheus/sensors/pcl2", - lp="1554.9,455.1", - penwidth=1, - pos="e,1732.1,383.02 1426.5,457.18 1482.5,443.68 1571.2,422.27 1647.9,403.6 1672.3,397.67 1699.1,391.11 1722.4,385.4"]; - n___lidar01 [URL=__lidar01, - height=0.5, - label="/lidar01", - pos="931.15,486.6", - shape=ellipse, - tooltip="/lidar01", - width=1.0652]; - n___lidar01 -> n___laser_to_pointcloud [URL=topic_3A__prometheus__sensors__2Dlidar_scan, - label="/prometheus/sensors/2Dlidar_scan", - lp="1186,487.1", - penwidth=1, - pos="e,1288.5,473.6 969.39,485.21 1037.7,482.72 1182.5,477.45 1278.2,473.97"]; - n___pub_goal [URL=__pub_goal, - height=0.5, - label="/pub_goal", - pos="114.14,334.6", - shape=ellipse, - tooltip="/pub_goal", - width=1.2818]; -}