LingxinMeng 1 year ago
parent
commit
c812c91b89
1 changed files with 61 additions and 0 deletions
  1. 61 0
      aarch64/topic-echo/main/main.go

+ 61 - 0
aarch64/topic-echo/main/main.go

@@ -1,15 +1,19 @@
 package main
 
 import (
+	pjiConfig "cicv-data-closedloop/aarch64/pji/master/package/config"
 	pjisuvConfig "cicv-data-closedloop/aarch64/pjisuv/master/package/config"
 	"cicv-data-closedloop/common/util"
 	"cicv-data-closedloop/kinglong_msgs"
+	"cicv-data-closedloop/pji_msgs"
 	"cicv-data-closedloop/pjisuv_msgs"
 	"fmt"
 	"github.com/bluenviron/goroslib/v2"
+	"github.com/bluenviron/goroslib/v2/pkg/msgs/diagnostic_msgs"
 	"github.com/bluenviron/goroslib/v2/pkg/msgs/geometry_msgs"
 	"github.com/bluenviron/goroslib/v2/pkg/msgs/nav_msgs"
 	"github.com/bluenviron/goroslib/v2/pkg/msgs/sensor_msgs"
+	"github.com/bluenviron/goroslib/v2/pkg/msgs/std_msgs"
 	"github.com/bluenviron/goroslib/v2/pkg/msgs/tf2_msgs"
 	"github.com/bluenviron/goroslib/v2/pkg/msgs/visualization_msgs"
 	"os"
@@ -24,6 +28,63 @@ func main() {
 	eType := util.ToString(os.Args[1])
 	topic := util.ToString(os.Args[2])
 
+	if eType == "pjisuv" {
+		//1 一致
+		if topic == pjiConfig.TopicOfDiagnostics {
+			_, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
+				Node:  rosNode,
+				Topic: topic,
+				Callback: func(data *diagnostic_msgs.DiagnosticArray) {
+					fmt.Println("收到话题", topic, "的数据", data)
+				}})
+		}
+		//2 一致
+		if topic == pjiConfig.TopicOfImu {
+			_, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
+				Node:  rosNode,
+				Topic: topic,
+				Callback: func(data *sensor_msgs.Imu) {
+					fmt.Println("收到话题", topic, "的数据", data)
+				}})
+		}
+		//3 一致
+		if topic == pjiConfig.TopicOfLocateInfo {
+			_, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
+				Node:  rosNode,
+				Topic: topic,
+				Callback: func(data *pji_msgs.LocateInfo) {
+					fmt.Println("收到话题", topic, "的数据", data)
+				}})
+		}
+		//4 一致
+		if topic == pjiConfig.TopicOfObstacleDetection {
+			_, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
+				Node:  rosNode,
+				Topic: topic,
+				Callback: func(data *std_msgs.UInt8) {
+					fmt.Println("收到话题", topic, "的数据", data)
+				}})
+		}
+		//5 一致
+		if topic == pjiConfig.TopicOfOdom {
+			_, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
+				Node:  rosNode,
+				Topic: topic,
+				Callback: func(data *nav_msgs.Odometry) {
+					fmt.Println("收到话题", topic, "的数据", data)
+				}})
+		}
+		//6 一致
+		if topic == pjiConfig.TopicOfSysInfo {
+			_, _ = goroslib.NewSubscriber(goroslib.SubscriberConf{
+				Node:  rosNode,
+				Topic: topic,
+				Callback: func(data *pji_msgs.SysInfo) {
+					fmt.Println("收到话题", topic, "的数据", data)
+				}})
+		}
+	}
+
 	if eType == "pjisuv" {
 		//1 一致
 		if topic == pjisuvConfig.TopicOfAmrPose {