diff --git a/onekey.sh b/onekey.sh
index 58b7d05..0322d66 100755
--- a/onekey.sh
+++ b/onekey.sh
@@ -95,17 +95,17 @@ check_camera(){
#检查使用哪种设备
if [ -n "$(lsusb -d 2bc5:0403)" ]; then
CAMERATYPE="astrapro"
- depthtolaser="/camera/depth/image_rect_raw"
+
camera_flag=$[$camera_flag + 1]
fi
if [ -n "$(lsusb -d 2bc5:0401)" ]; then
CAMERATYPE="astra"
- depthtolaser="/camera/depth/image_raw"
+
camera_flag=$[$camera_flag + 1]
fi
if [ -n "$(lsusb -d 8086:0b07)" ]; then
CAMERATYPE="d435"
- depthtolaser="/camera/depth/image_rect_raw"
+
camera_flag=$[$camera_flag + 1]
fi
@@ -507,11 +507,11 @@ spark_navigation_3d(){
echo -e "${Info}"
echo && stty erase ^? && read -p "按回车键(Enter)开始:"
if [[ "${SLAMTYPE}" == "2d" ]]; then
- print_command "roslaunch spark_navigation amcl_demo_rviz.launch camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}"
- roslaunch spark_navigation amcl_demo_rviz.launch camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}
+ print_command "roslaunch spark_navigation amcl_demo_rviz.launch camera_type_tel:=${CAMERATYPE}"
+ roslaunch spark_navigation amcl_demo_rviz.launch camera_type_tel:=${CAMERATYPE}
else
- print_command "roslaunch spark_rtabmap spark_rtabmap_nav.launch camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}"
- roslaunch spark_rtabmap spark_rtabmap_nav.launch camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}
+ print_command "roslaunch spark_rtabmap spark_rtabmap_nav.launch camera_type_tel:=${CAMERATYPE}"
+ roslaunch spark_rtabmap spark_rtabmap_nav.launch camera_type_tel:=${CAMERATYPE}
fi
}
@@ -833,14 +833,14 @@ spark_build_map_3d(){
echo -e "${Tip}"
echo && stty erase ^? && read -p "请选择是否继续y/n:" choose
if [[ "${choose}" == "y" ]]; then
- print_command "roslaunch spark_rtabmap spark_rtabmap_teleop.launch camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}"
- roslaunch spark_rtabmap spark_rtabmap_teleop.launch camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}
+ print_command "roslaunch spark_rtabmap spark_rtabmap_teleop.launch camera_type_tel:=${CAMERATYPE}"
+ roslaunch spark_rtabmap spark_rtabmap_teleop.launch camera_type_tel:=${CAMERATYPE}
else
return
fi
else
- print_command "roslaunch spark_slam depth_slam_teleop.launch slam_methods_tel:=${SLAMTYPE} camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}"
- roslaunch spark_slam depth_slam_teleop.launch slam_methods_tel:=${SLAMTYPE} camera_type_tel:=${CAMERATYPE} depthtolaser:=${depthtolaser}
+ print_command "roslaunch spark_slam depth_slam_teleop.launch slam_methods_tel:=${SLAMTYPE} camera_type_tel:=${CAMERATYPE}"
+ roslaunch spark_slam depth_slam_teleop.launch slam_methods_tel:=${SLAMTYPE} camera_type_tel:=${CAMERATYPE}
fi
}
diff --git a/src/spark_app/spark_navigation/launch/amcl_demo_rviz.launch b/src/spark_app/spark_navigation/launch/amcl_demo_rviz.launch
index be55d5d..6457657 100755
--- a/src/spark_app/spark_navigation/launch/amcl_demo_rviz.launch
+++ b/src/spark_app/spark_navigation/launch/amcl_demo_rviz.launch
@@ -3,7 +3,7 @@
-
+
@@ -11,20 +11,8 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
diff --git a/src/spark_app/spark_rtabmap/launch/rtab_demo.launch b/src/spark_app/spark_rtabmap/launch/rtab_demo.launch
index f0868a2..caabd84 100755
--- a/src/spark_app/spark_rtabmap/launch/rtab_demo.launch
+++ b/src/spark_app/spark_rtabmap/launch/rtab_demo.launch
@@ -2,16 +2,17 @@
-
+
-
-
-
+
+
+
+
diff --git a/src/spark_app/spark_rtabmap/launch/spark_mapping_astrapro.launch b/src/spark_app/spark_rtabmap/launch/spark_mapping_astrapro.launch
index a2be635..8b07004 100755
--- a/src/spark_app/spark_rtabmap/launch/spark_mapping_astrapro.launch
+++ b/src/spark_app/spark_rtabmap/launch/spark_mapping_astrapro.launch
@@ -25,7 +25,7 @@
-
+
@@ -83,7 +83,7 @@
-
+
diff --git a/src/spark_app/spark_rtabmap/launch/spark_rtabmap_nav.launch b/src/spark_app/spark_rtabmap/launch/spark_rtabmap_nav.launch
index 061566c..46f0cda 100755
--- a/src/spark_app/spark_rtabmap/launch/spark_rtabmap_nav.launch
+++ b/src/spark_app/spark_rtabmap/launch/spark_rtabmap_nav.launch
@@ -3,7 +3,7 @@
-
+
@@ -12,11 +12,12 @@
-
-
+
+
+
diff --git a/src/spark_app/spark_rtabmap/launch/spark_rtabmap_teleop.launch b/src/spark_app/spark_rtabmap/launch/spark_rtabmap_teleop.launch
index 3a70030..285ce51 100755
--- a/src/spark_app/spark_rtabmap/launch/spark_rtabmap_teleop.launch
+++ b/src/spark_app/spark_rtabmap/launch/spark_rtabmap_teleop.launch
@@ -1,13 +1,13 @@
-
+
-
+
diff --git a/src/spark_app/spark_slam/launch/depth_slam.launch b/src/spark_app/spark_slam/launch/depth_slam.launch
index 1efa982..77ec715 100755
--- a/src/spark_app/spark_slam/launch/depth_slam.launch
+++ b/src/spark_app/spark_slam/launch/depth_slam.launch
@@ -2,7 +2,6 @@
-
@@ -12,25 +11,11 @@
+
+
+
+
-
-
-
diff --git a/src/spark_app/spark_slam/launch/depth_slam_teleop.launch b/src/spark_app/spark_slam/launch/depth_slam_teleop.launch
index 2671509..6b8338c 100755
--- a/src/spark_app/spark_slam/launch/depth_slam_teleop.launch
+++ b/src/spark_app/spark_slam/launch/depth_slam_teleop.launch
@@ -2,12 +2,10 @@
-
-
diff --git a/src/spark_driver/camera/camera_driver_transfer/launch/astra_p2s.launch b/src/spark_driver/camera/camera_driver_transfer/launch/astra_p2s.launch
new file mode 100755
index 0000000..cde53d2
--- /dev/null
+++ b/src/spark_driver/camera/camera_driver_transfer/launch/astra_p2s.launch
@@ -0,0 +1,29 @@
+
+
+
+
+
+
+
+
+ target_frame: camera_link
+ transform_tolerance: 0.01
+ min_height: 0.0
+ max_height: 1.0
+
+ angle_min: -1.5708
+ angle_max: 1.5708
+ angle_increment: 0.0087
+ scan_time: 0.3333
+ range_min: 0.45
+ range_max: 4.0
+ use_inf: true
+
+ #concurrency_level affects number of pc queued for processing and the number of threadsused
+ # 0: Detect number of cores
+ # 1: Single threaded
+ # 2: inf : Parallelism level
+ concurrency_level: 1
+
+
+
diff --git a/src/spark_driver/camera/camera_driver_transfer/launch/astrapro_p2s.launch b/src/spark_driver/camera/camera_driver_transfer/launch/astrapro_p2s.launch
new file mode 100755
index 0000000..cde53d2
--- /dev/null
+++ b/src/spark_driver/camera/camera_driver_transfer/launch/astrapro_p2s.launch
@@ -0,0 +1,29 @@
+
+
+
+
+
+
+
+
+ target_frame: camera_link
+ transform_tolerance: 0.01
+ min_height: 0.0
+ max_height: 1.0
+
+ angle_min: -1.5708
+ angle_max: 1.5708
+ angle_increment: 0.0087
+ scan_time: 0.3333
+ range_min: 0.45
+ range_max: 4.0
+ use_inf: true
+
+ #concurrency_level affects number of pc queued for processing and the number of threadsused
+ # 0: Detect number of cores
+ # 1: Single threaded
+ # 2: inf : Parallelism level
+ concurrency_level: 1
+
+
+
diff --git a/src/spark_driver/camera/camera_driver_transfer/launch/d435_p2s.launch b/src/spark_driver/camera/camera_driver_transfer/launch/d435_p2s.launch
new file mode 100755
index 0000000..800270b
--- /dev/null
+++ b/src/spark_driver/camera/camera_driver_transfer/launch/d435_p2s.launch
@@ -0,0 +1,29 @@
+
+
+
+
+
+
+
+
+ target_frame: camera_link
+ transform_tolerance: 0.01
+ min_height: 0.0
+ max_height: 1.0
+
+ angle_min: -1.5708
+ angle_max: 1.5708
+ angle_increment: 0.0087
+ scan_time: 0.3333
+ range_min: 0.45
+ range_max: 4.0
+ use_inf: true
+
+ #concurrency_level affects number of pc queued for processing and the number of threadsused
+ # 0: Detect number of cores
+ # 1: Single threaded
+ # 2: inf : Parallelism level
+ concurrency_level: 1
+
+
+