PolibaX / rclgo

Go bindings for ROS2. Forked from https://github.com/tiiuae/rclgo
Apache License 2.0
2 stars 1 forks source link

Subscriber not reading topic #4

Open dp1140a opened 1 month ago

dp1140a commented 1 month ago

I am trying to write a test to read a PX4 messages. Im running PX$ in SITL with Gazebo and the MicroXRCEAgent. I can see the topic "/fmu/out/vehicle_gps_position" and echo the data. When I run the PX$ subscriber example in C++ it reads the topic and I see:

RECEIVED VEHICLE GPS POSITION DATA
==================================
ts: 1729878465741305
lat: 47.398
lon: 8.54616
alt: 0.747968
alt_ellipsoid: 0.747968
s_variance_m_s: 0.4
c_variance_rad: 0.1
fix_type: 
eph: 0.9
epv: 1.78
hdop: 0.7
vdop: 1.1
noise_per_ms: 0
vel_m_s: 0.0422516
vel_n_m_s: 0.0422439
vel_e_m_s: -0.00080613
vel_d_m_s: 0.104274
cog_rad: -0.0190804
vel_ned_valid: 1
timestamp_time_relative: 0
time_utc_usec: 0
satellites_used: 

heading: nan
heading_offset: nan

In the console. This is what it should do.

But when I try to run the exact same subscriber in RCLGO nothing prints to the screen. No error nothing:

go run .
Publisher Count: 0
[INFO] [1729878544.317985074] [position_publisher]: Position_Publisher Node running

Heres the strange part. When I launch a separate Publisher on the same topic, the subscriber sees that message and prints it like it should.

So why is it not seeing the initial PX4 messages coming from PX4.

Steps to Recreate

Terminal1:

cd Micro-XRCE-DDS-Agent/build
MicroXRCEAgent udp4 -p 8888

Terminal 2:

cd PX4-Autopilot
make px4_sitl gz_x500

Terminal 3:

ros2 topic topic list <- You should see /fmu/out/vehicle_gps_position
ros2 topic echo  /fmu/out/vehicle_gps_position

Modify the RCLGo Subscriber Example to use PX4 Messages and subscribe to the /fmu/out/vehicle_gps_position topic Terminal4:

go run .
Publisher Count: 0
[INFO] [1729878544.317985074] [position_publisher]: Position_Publisher Node running

Then if you like launch a publisher on the same topic and you will see that message get picked up.

For reference here is the code I am using for my subscriber, but I have also used the subscriber example in this repo.

package main

import (
    "context"
    "fmt"
    "os/signal"
    "syscall"
    "time"

    "os"

    "github.com/merlindrones/gomavlib/pkg/message"
    "github.com/merlindrones/rclgo/pkg/rclgo"
    msg "swarm/msgs/px4_msgs/msg"
)

const (
    _GLOBAL_POS = "/fmu/out/vehicle_gps_position"
    _NODE_NAME  = "position_subscriber"
)

type PositionNode struct {
    node   *rclgo.Node
    config PositionNodeConfig
}

type PositionNodeConfig struct {
    interval time.Duration
}

func NewPositionNode(rclArgs *rclgo.Args, config PositionNodeConfig) (*PositionNode, error) {
    err := rclgo.Init(rclArgs)
    if err != nil {
        return nil, fmt.Errorf("failed to initialize rclgo: %v", err)
    }

    pn := &PositionNode{
        config: config,
    }
    return pn, nil
}

// run runs the node to set up a ROS2 subscription for VehicleGlobalPosition messages.
// On the interval basis this should publish the node position on the swarm net
func (pn *PositionNode) spin() (err error) {
    pn.node, err = rclgo.NewNode(_NODE_NAME, "")
    if err != nil {
        return fmt.Errorf("failed to create node: %v", err)
    }
    defer pn.node.Close()
    sub, err := msg.NewSensorGpsSubscription(pn.node, "/fmu/out/vehicle_gps_position",
        nil,
        func(msg *msg.SensorGps, info *rclgo.MessageInfo, err error) {
            if err != nil {
                pn.node.Logger().Errorf("failed to receive message: %v", err)
                return
            }

            pn.node.Logger().Infof("Received: %#v", msg.Timestamp)

        })
    if err != nil {
        return fmt.Errorf("failed to create subscriber: %v", err)
    }
    count, err := sub.GetPublisherCount()
    if err != nil {
        fmt.Println("Cant get pub count")
    }
    fmt.Printf("Publisher Count: %d\n", count)
    defer sub.Close()
    ctx, cancel := signal.NotifyContext(context.Background(), syscall.SIGINT, syscall.SIGTERM)
    defer cancel()

    ws, err := rclgo.NewWaitSet()
    if err != nil {
        return fmt.Errorf("failed to create waitset: %v", err)
    }
    defer ws.Close()
    ws.AddSubscriptions(sub.Subscription)
    pn.node.Logger().Infof("Position_Publisher Node running")
    return ws.Run(ctx)
}

func main() {
    rclArgs, _, err := rclgo.ParseArgs(os.Args[1:])
    if err != nil {
        fmt.Errorf("failed to parse ROS args: %v", err)
        os.Exit(1)
    }
    pn, err := NewPositionNode(rclArgs, PositionNodeConfig{})
    if err != nil {
        fmt.Fprintln(os.Stderr, err)
        os.Exit(1)
    }
    defer rclgo.Uninit()
    if err := pn.spin(); err != nil {
        fmt.Fprintln(os.Stderr, err)
        os.Exit(1)
    }
}
dp1140a commented 1 month ago

UPDATE: So it turns out you just need to pass in Subscription Option with a QOS Profile. I went back and looked at the PX4 Subscription example in C++ and saw they were using a QOS Profile. Thought I would try it and Voila!

So change

sub, err := msg.NewSensorGpsSubscription(pn.node, "/fmu/out/vehicle_gps_position",
        nil,
        func(msg *msg.SensorGps, info *rclgo.MessageInfo, err error) {
            if err != nil {
                pn.node.Logger().Errorf("failed to receive message: %v", err)
                return
            }

            pn.node.Logger().Infof("Received: %#v", msg.Timestamp)

        })

to

opts := &rclgo.SubscriptionOptions{
        Qos: rclgo.QosProfile{
            History:                      1,
            Depth:                        5,
            Reliability:                  2,
            Durability:                   2,
            Deadline:                     0,
            Lifespan:                     0,
            Liveliness:                   0,
            LivelinessLeaseDuration:      0,
            AvoidRosNamespaceConventions: false,
        },
    }

sub, err := msg.NewSensorGpsSubscription(pn.node, "/fmu/out/vehicle_gps_position",
        opts,
        func(msg *msg.SensorGps, info *rclgo.MessageInfo, err error) {
            if err != nil {
                pn.node.Logger().Errorf("failed to receive message: %v", err)
                return
            }

            pn.node.Logger().Infof("Received: %#v", msg.Timestamp)

        })

AND IT WORKS!!! Sorry I'm pretty stoked.