cicv 2 달 전
부모
커밋
bb076421c7

+ 20 - 41
aarch64/pjibot_clean/清洁机器人默认配置文件-cloud-config.yaml

@@ -43,8 +43,11 @@ map-buf-files:
   - /root/pjirobot/data/mapBuf/map.yaml
   - /root/pjirobot/data/mapBuf/map_type.json
   - /root/pjirobot/data/mapBuf/param.yaml
+  - /root/pjirobot/data/mapBuf/segment_map.png
+  - /root/pjirobot/data/mapBuf/segment_map_original.png
   - /root/pjirobot/data/mapBuf/stations.json
   - /root/pjirobot/data/mapBuf/stations_init.json
+  - /root/pjirobot/data/mapBuf/version.json
 map-bag-path: /root/cicv-data-closedloop/map.bag
 bag-data-dir: /root/pjirobot/data/cicv-data-closedloop/data/
 bag-copy-dir: /root/pjirobot/data/cicv-data-closedloop/copy/
@@ -71,32 +74,28 @@ hosts:
     rosbag:
       path: "/opt/ros/melodic/bin/rosbag"
       envs:
-        - "C_INCLUDE_PATH=/usr/include/drm:"
+        - "C_INCLUDE_PATH=/usr/include/libdrm:"
         - "USER=root"
-        - "ROS_PACKAGE_PATH=/opt/ros/melodic/share"
-        - "LD_LIBRARY_PATH=/opt/ros/melodic/lib:/opt/ros/melodic/lib/aarch64-linux-gnu"
-        - "ROS_ETC_DIR=/opt/ros/melodic/etc/ros"
-        - "SHLVL=1"
+        - "ROS_PACKAGE_PATH=/opt/ros/noetic/share"
+        - "LD_LIBRARY_PATH=/opt/ros/noetic/lib"
+        - "ROS_ETC_DIR=/opt/ros/noetic/etc/ros"
+        - "SHLVL=0"
         - "HOME=/root"
-        - "ROS_PYTHON_VERSION=2"
+        - "ROS_PYTHON_VERSION=3"
         - "PCMANFM_OUTLINE_MODE=on"
-        - "CPLUS_INCLUDE_PATH=/usr/include/drm:"
-        - "ROS_DISTRO=melodic"
+        - "CPLUS_INCLUDE_PATH=/usr/include/libdrm:"
+        - "ROS_DISTRO=noetic"
         - "ROS_VERSION=1"
-        - "PKG_CONFIG_PATH=/opt/ros/melodic/lib/pkgconfig"
-        - "PATH=/opt/ros/melodic/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/usr/local/go/bin:/root/go/bin"
-        - "ROS_ROOT=/opt/ros/melodic/share/ros"
+        - "PKG_CONFIG_PATH=/opt/ros/noetic/lib/pkgconfig:/usr/local/lib/pkgconfig:"
+        - "PATH=/opt/ros/noetic/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/usr/local/go/bin:/root/go/bin"
+        - "ROS_ROOT=/opt/ros/noetic/share/ros"
         - "ROSLISP_PACKAGE_DIRECTORIES="
-        - "ROS_MASTER_URI=http://192.168.1.104:11311"
-        - "PYTHONPATH=/opt/ros/melodic/lib/python2.7/dist-packages"
+        - "ROS_MASTER_URI=http://localhost:11311"
+        - "PYTHONPATH=/opt/ros/noetic/lib/python3/dist-packages"
         - "ROS_HOSTNAME=192.168.1.104"
-        - "CMAKE_PREFIX_PATH=/opt/ros/melodic"
-    topics: # /amcl_pose,/ob_camera_01/color/image_raw,/ob_camera_02/color/image_raw,/diagnostics,/locate_info,/obstacle_detection,/odom,/move_base/global_costmap/costmap,/move_base/global_costmap/costmap_updates,/move_base/local_costmap/costmap,/move_base/local_costmap/costmap_updates,/scan,/scan_map_icp_amcl_node/scan_point_transformed,/sys_info,/imu,/depth_scan_02,/map,/scan_filtered,/sonar_left,/sonar_right,/sonar_mid,/sonar_rmid,/tf,/tf_static,/cmd_vel,/move_base/DWAPlannerROS/global_plan,/move_base/DWAPlannerROS/local_plan,/move_base/GlobalPlanner/plan,/move_base/global_costmap/footprint,/move_base/local_costmap/footprint,/robot_pose_tf
+        - "CMAKE_PREFIX_PATH=/opt/ros/noetic"
+    topics:
       - /amcl_pose # /amcl
-      - /ob_camera_01/color/image_raw # /ob_camera_01/camera
-      #      - /ob_camera_01/depth/points # /ob_camera_01/camera
-      - /ob_camera_02/color/image_raw # /ob_camera_02/camera
-      #      - /ob_camera_02/depth/points # /ob_camera_02/camera
       - /diagnostics # /amcl /node_diagnostics
       - /locate_info # /localization_monitor_node
       - /obstacle_detection # /move_base
@@ -108,16 +107,10 @@ hosts:
       - /scan # /ltme_node
       - /scan_map_icp_amcl_node/scan_point_transformed # /scan_map_icp_amcl_node
       - /sys_info
-      #      - /cmd_vel
       - /imu
       # 算法评价新增
-      - /depth_scan_02
       - /map
-      - /scan_filtered
-      - /sonar_left
-      - /sonar_right
-      - /sonar_mid
-      - /sonar_rmid
+      - /sonar
       - /tf
       - /tf_static
       - /cmd_vel
@@ -133,8 +126,6 @@ full-collect: true # 控制是否根据不同的触发器采集不通的topic,
 triggers:
   - label: detectfault
     topics:
-      - /camera/color/image_raw
-      - /camera/depth/points
       - /diagnostics
       - /locate_info
       - /obstacle_detection
@@ -144,8 +135,6 @@ triggers:
       - /scan_map_icp_amcl_node/scan_point_transformed
   - label: unstabledriving
     topics:
-      - /camera/color/image_raw
-      - /camera/depth/points
       - /diagnostics
       - /locate_info
       - /obstacle_detection
@@ -155,8 +144,6 @@ triggers:
       - /scan_map_icp_amcl_node/scan_point_transformed
   - label: locationfailed
     topics:
-      - /camera/color/image_raw
-      - /camera/depth/points
       - /diagnostics
       - /locate_info
       - /obstacle_detection
@@ -166,8 +153,6 @@ triggers:
       - /scan_map_icp_amcl_node/scan_point_transformed
   - label: obstacledetection
     topics:
-      - /camera/color/image_raw
-      - /camera/depth/points
       - /diagnostics
       - /locate_info
       - /obstacle_detection
@@ -177,8 +162,6 @@ triggers:
       - /scan_map_icp_amcl_node/scan_point_transformed
   - label: overspeed
     topics:
-      - /camera/color/image_raw
-      - /camera/depth/points
       - /diagnostics
       - /locate_info
       - /obstacle_detection
@@ -188,8 +171,6 @@ triggers:
       - /scan_map_icp_amcl_node/scan_point_transformed
   - label: cpuoveroccupied
     topics:
-      - /camera/color/image_raw
-      - /camera/depth/points
       - /diagnostics
       - /locate_info
       - /obstacle_detection
@@ -199,12 +180,10 @@ triggers:
       - /scan_map_icp_amcl_node/scan_point_transformed
   - label: memoveroccupied
     topics:
-      - /camera/color/image_raw
-      - /camera/depth/points
       - /diagnostics
       - /locate_info
       - /obstacle_detection
       - /odom
       - /move_base/global_costmap/costmap
       - /move_base/global_costmap/costmap_updates
-      - /scan_map_icp_amcl_node/scan_point_transformed
+      - /scan_map_icp_amcl_node/scan_point_transformed

+ 0 - 69
kinglong_msgs/common_msgs.go

@@ -1,69 +0,0 @@
-package kinglong_msgs
-
-import (
-	"github.com/bluenviron/goroslib/v2/pkg/msg"
-	"github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
-)
-
-type FaultInfo struct {
-	msg.Package  `ros:"common_msgs"`
-	TimestampSec float64
-	ModuleName   string
-	Version      string
-	ErrorCode    int32
-	Msg          string
-	FaultLevel   int8
-	FaultType    int8
-}
-
-type Header struct {
-	msg.Package    `ros:"common_msgs"`
-	SequenceNum    int32
-	TimeStamp      float64
-	ModuleName     string
-	Version        string
-	FaultVec       FaultVec
-	TimeStatistics TimeStatistics
-}
-
-type FaultVec struct {
-	msg.Package      `ros:"common_msgs"`
-	InfoVec          []FaultInfo
-	ModuleFaultLevel int32
-}
-
-type TimeStatistics struct {
-	msg.Package      `ros:"common_msgs"`
-	DevTimeStatusMsg []TimeStatus
-	SendingTimestamp float64
-}
-
-type TimeStatus struct {
-	msg.Package         `ros:"common_msgs"`
-	Dtime               float64
-	SourceNodeName      string
-	DestinationNodeName string
-}
-
-type Retrieval struct {
-	msg.Package            `ros:"common_msgs"`
-	Header                 std_msgs.Header `rosname:"header"`
-	AsVehAccelerationValue float64         `rosname:"AS_Veh_Acceleration_Value"` // 惯导采集到的加速度
-	AsDriverTakeoverReq    int16           `rosname:"AS_Driver_TakeOver_Req"`    // 驾驶员接管提醒(2B9)
-	VcuAccelPosValue       float64         `rosname:"VCU_Accel_Pos_Value"`       // 实际加速踏板位置
-	VcuBrkPelPosValue      float64         `rosname:"VCU_BrkPel_Pos_Value"`      // 实际制动踏板位置
-	VcuRealSpeed           float64         `rosname:"VCU_Real_Speed"`            // 当前车速
-	VcuCurrentGear         int16           `rosname:"VCU_Current_Gear"`          // 当前档位
-	VcuParkingSt           int16           `rosname:"VCU_Parking_St"`            // 当前P档位
-	AutoDLimitInReason     int16           `rosname:"AutoD_Limitin_Reason"`      // 限制进入自动驾驶原因
-	EmergencyStopReason    int16           `rosname:"Emergency_Stop_Reason"`     // 紧急停车激活原因
-	VcuDriverTakeoverReq   int16           `rosname:"VCU_Driver_TakeOver_Req"`   // 驾驶员接管提醒(2BA)
-	VcuVehicleDriveModeSt  int16           `rosname:"VCU_Vehicle_Drive_Mode_St"` // 车辆驾驶模式
-	AutoDOutReason         int16           `rosname:"AutoD_Out_Reason"`          // 退出自动驾驶原因
-	BrakeSysFaultSt        int16           `rosname:"Brak_Sys_Fault_St"`         // 制动系统故障
-	StrgAngleRealValue     float64         `rosname:"Strg_Angle_Real_Value"`     // 方向盘实际转角
-	StrgAngleSpdValue      float64         `rosname:"Strg_Angle_Spd_Value"`      // 方向盘当前实际速度反馈
-	StrgWorkmodeSt         int16           `rosname:"Strg_WorkMode_St"`          // 当前系统实际工作模式
-	BCHornSt               int16           `rosname:"BC_Horn_St"`                // 喇叭状态
-
-}

+ 0 - 54
kinglong_msgs/control_msgs.go

@@ -1,54 +0,0 @@
-package kinglong_msgs
-
-import (
-	"github.com/bluenviron/goroslib/v2/pkg/msg"
-	"github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
-)
-
-type JinlongControlCommand struct {
-	msg.Package                   `ros:"autoware_msgs"`
-	Header                        std_msgs.Header
-	ASStrgAngleReq                float64 `rosname:"AS_Strg_Angle_Req"`
-	ASStrgWorkModeReq             int16   `rosname:"AS_Strg_WorkMode_Req"`
-	ASStrg0Enable                 int16   `rosname:"AS_Strg0_Enable"`
-	ASSteeringTorqueSuperposition float64 `rosname:"AS_Steering_torque_superposition"`
-	ASStrgSpdReq                  float64 `rosname:"AS_Strg_Spd_Req"`
-	ASStrg1Enable                 int16   `rosname:"AS_Strg1_Enable"`
-	ASStrgLifeSignal              int16   `rosname:"AS_Strg_Life_Signal"`
-	ASAutoDReq                    int16   `rosname:"AS_AutoD_Req"`
-	ASLongitCtrlmode              int16   `rosname:"AS_Longit_Ctrlmode"`
-	ASAutoDEmergBrkRelease        int16   `rosname:"AS_AutoD_EmergBrk_Release"`
-	ASAutoDCollisionRelease       int16   `rosname:"AS_AutoD_Collision_Release"`
-	ASAutoDAccelPosReq            float64 `rosname:"AS_AutoD_Accel_Pos_Req"`
-	ASAutoDShiftReq               int16   `rosname:"AS_AutoD_Shift_Req"`
-	ASAutoDPShiftReq              int16   `rosname:"AS_AutoD_P_Shift_Req"`
-	ASAutoDBrkModeReq             int16   `rosname:"AS_AutoD_BrkMode_Req"`
-	ASAutoDBrkPelPosReq           float64 `rosname:"AS_AutoD_BrkPelPos_Req"`
-	ASAutoDSpdLimit               float64 `rosname:"AS_AutoD_Spd_Limit"`
-	ASAutoAccelerationReq         float64 `rosname:"AS_Auto_Acceleration_Req"`
-	ASAutoDLifeSignal             int16   `rosname:"AS_AutoD_Life_Signal"`
-	ASAutoDSpdReq                 float64 `rosname:"AS_AutoD_Spd_Req"`
-	ASSpdLifeSignal               int16   `rosname:"AS_Spd_Life_Signal"`
-	ASAlarmLampReq                int16   `rosname:"AS_AlarmLamp_Req"`
-	ASFrontDoorCtrlReq            int16   `rosname:"AS_Front_Door_Ctrl_Req"`
-	ASLowBeamStartReq             int16   `rosname:"AS_LowBeam_Start_Req"`
-	ASTurnLeftLightStartReq       int16   `rosname:"AS_TurnLeftLight_Start_Req"`
-	ASTurnRightLightStartReq      int16   `rosname:"AS_TurnRightLight_Start_Req"`
-	ASMiniLightStartReq           int16   `rosname:"AS_MiniLight_Start_Req"`
-	ASHornStartReq                int16   `rosname:"AS_Horn_Start_Req"`
-	ASTreadleOperatingReq         int16   `rosname:"AS_Treadle_Operating_Req"`
-	ASFDoorButtonLockReq          int16   `rosname:"AS_FDoorButtonLock_Req"`
-	ASMidDoorCtrlReq              int16   `rosname:"AS_Mid_Door_Ctrl_Req"`
-	ASMDoorButtonLockReq          int16   `rosname:"AS_MDoorButtonLock_Req"`
-	ASRearDoorCtrlReq             int16   `rosname:"AS_Rear_Door_Ctrl_Req"`
-	ASRDoorButtonLockReq          int16   `rosname:"AS_RDoorButtonLock_Req"`
-	ASFrontFogReq                 int16   `rosname:"AS_FrontFog_Req"`
-	ASRearFogReq                  int16   `rosname:"AS_RearFog_Req"`
-	ASWarninglightReq             int16   `rosname:"AS_Warninglight_Req"`
-	ASHighBeamStartReq            int16   `rosname:"AS_HighBeam_Start_Req"`
-	TargetX                       float64
-	TargetY                       float64
-	LateralError                  float64
-	Velocity                      float64
-	AutoMode                      int16
-}

+ 0 - 104
kinglong_msgs/perception_msgs.go

@@ -1,104 +0,0 @@
-package kinglong_msgs
-
-import (
-	"github.com/bluenviron/goroslib/v2/pkg/msg"
-	"github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
-)
-
-// PerceptionObjects v2304
-type PerceptionObjects struct {
-	msg.Package `ros:"perception_msgs"`
-	Header      Header
-	Objs        []Object
-	Cells       []ObstacleCell
-}
-
-type Object struct {
-	msg.Package    `ros:"perception_msgs"`
-	Id             uint32
-	X              float32
-	Y              float32
-	Z              float32
-	Vxrel          float32
-	Vyrel          float32
-	Xabs           float64
-	Yabs           float64
-	Vxabs          float32
-	Vyabs          float32
-	Width          float32
-	Length         float32
-	Height         float32
-	Speed          float32
-	Heading        float32
-	Type           uint8
-	Source         uint8
-	Confidence     float32
-	Age            uint32
-	Velocitystatus uint8
-	Cells          []ObstacleCell
-}
-
-type ObstacleCell struct {
-	msg.Package `ros:"perception_msgs"`
-	Idc         int32
-	X           float64
-	Y           float64
-	Xg          float64
-	Yg          float64
-}
-
-type PerceptionLocalization struct {
-	msg.Package `ros:"perception_msgs"`
-
-	Header      std_msgs.Header
-	FrameUnmber uint64
-	FusionLevel int8
-	Status      int8
-	Roll        float64
-	Pitch       float64
-	Yaw         float64
-	RollStd     float32
-	PitchStd    float32
-	YawStd      float32
-
-	Qw float64
-	Qx float64
-	Qy float64
-	Qz float64
-
-	AngularVelocityX float64
-	AngularVelocityY float64
-	AngularVelocityZ float64
-
-	Latitude     float64
-	Longitude    float64
-	Altitude     float64
-	LatitudeStd  float32
-	LongitudeStd float32
-	AltitudeStd  float32
-
-	PositionX    float64
-	PositionY    float64
-	PositionZ    float64
-	PositionXStd float32
-	PositionYStd float32
-	PositionZStd float32
-
-	VelocityX    float64
-	VelocityY    float64
-	VelocityZ    float64
-	VelocityXStd float32
-	VelocityYStd float32
-	VelocityZStd float32
-
-	VelocityRx    float64
-	VelocityRy    float64
-	VelocityRz    float64
-	VelocityRxStd float32
-	VelocityRyStd float32
-	VelocityRzStd float32
-
-	AccelX float64
-	AccelY float64
-	AccelZ float64
-}