Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ Features:
* [node-endpoint-custom-server](examples/node-endpoint-custom-server/main.go)
* [node-message-read](examples/node-message-read/main.go)
* [node-message-write](examples/node-message-write/main.go)
* [node-command-protocol](examples/node-command-protocol/main.go)
* [node-signature](examples/node-signature/main.go)
* [node-dialect-absent](examples/node-dialect-absent/main.go)
* [node-dialect-custom](examples/node-dialect-custom/main.go)
Expand Down
4 changes: 4 additions & 0 deletions channel.go
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,10 @@ func (ch *Channel) runReader() error {

evt := &EventFrame{fr, ch}

if ch.node.nodeCommand != nil {
ch.node.nodeCommand.onEventFrame(evt)
}

if ch.node.nodeStreamRequest != nil {
ch.node.nodeStreamRequest.onEventFrame(evt)
}
Expand Down
146 changes: 146 additions & 0 deletions examples/node-command-protocol/main.go
Original file line number Diff line number Diff line change
@@ -0,0 +1,146 @@
// Package main contains an example.
package main

import (
"log"
"time"

"github.com/bluenviron/gomavlib/v3"
"github.com/bluenviron/gomavlib/v3/pkg/dialects/common"
)

// This example shows how to:
// 1. Create a node that supports the command protocol
// 2. Send a COMMAND_LONG and wait for COMMAND_ACK response
// 3. Handle command results including progress updates

func main() {
// Create a node with command protocol support
// (automatically enabled when a dialect is provided)
node := &gomavlib.Node{
Endpoints: []gomavlib.EndpointConf{
gomavlib.EndpointSerial{
Device: "/dev/ttyUSB0",
Baud: 57600,
},
},
Dialect: common.Dialect, // Required for command protocol
OutVersion: gomavlib.V2,
OutSystemID: 255, // Ground station
}

err := node.Initialize()
if err != nil {
panic(err)
}
defer node.Close()

var targetChannel *gomavlib.Channel

log.Println("Waiting for connection...")

// Wait for a channel to open and send a command
for evt := range node.Events() {
switch e := evt.(type) {
case *gomavlib.EventChannelOpen:
targetChannel = e.Channel
log.Printf("Channel opened: %s\n", targetChannel)

case *gomavlib.EventFrame:
// Wait for heartbeat to know target system ID
if _, ok := e.Message().(*common.MessageHeartbeat); ok {
log.Printf("Received heartbeat from system %d, component %d\n",
e.SystemID(), e.ComponentID())

// Send ARM command with progress tracking
log.Println("Sending ARM command...")
var resp *gomavlib.CommandResponse
var cmdErr error
resp, cmdErr = node.SendCommandLong(&common.MessageCommandLong{
TargetSystem: e.SystemID(),
TargetComponent: e.ComponentID(),
Command: common.MAV_CMD_COMPONENT_ARM_DISARM,
Param1: 1,
Param2: 0,
Param3: 0,
Param4: 0,
Param5: 0,
Param6: 0,
Param7: 0,
}, &gomavlib.CommandOptions{
Timeout: 5 * time.Second,
OnProgress: func(progress uint8) {
if progress == 255 {
log.Println("Command in progress (progress unknown)")
} else {
log.Printf("Command progress: %d%%\n", progress)
}
},
})

if cmdErr != nil {
log.Printf("Command failed: %v\n", err)
return
}

// Check result
log.Printf("Command completed in %v\n", resp.ResponseTime)
switch resp.Result {
case uint64(common.MAV_RESULT_ACCEPTED):
log.Println("✓ Command ACCEPTED - Vehicle armed!")

// Example: Send another command (DISARM)
time.Sleep(2 * time.Second)
log.Println("Sending DISARM command...")
resp, cmdErr = node.SendCommandLong(&common.MessageCommandLong{
TargetSystem: e.SystemID(),
TargetComponent: e.ComponentID(),
Command: common.MAV_CMD_COMPONENT_ARM_DISARM,
Param1: 0,
Param2: 0,
Param3: 0,
Param4: 0,
Param5: 0,
Param6: 0,
Param7: 0,
}, &gomavlib.CommandOptions{
Timeout: 5 * time.Second,
})

if cmdErr != nil {
log.Printf("DISARM command failed: %v\n", err)
return
}

if resp.Result == uint64(common.MAV_RESULT_ACCEPTED) {
log.Println("✓ Vehicle disarmed!")
} else {
log.Printf("DISARM command failed: %v\n", resp.Result)
}

return

case uint64(common.MAV_RESULT_TEMPORARILY_REJECTED):
log.Println("✗ Command TEMPORARILY REJECTED - retry later")
log.Printf(" Additional info: %d\n", resp.ResultParam2)

case uint64(common.MAV_RESULT_DENIED):
log.Println("✗ Command DENIED")
log.Printf(" Additional info: %d\n", resp.ResultParam2)

case uint64(common.MAV_RESULT_UNSUPPORTED):
log.Println("✗ Command UNSUPPORTED")

case uint64(common.MAV_RESULT_FAILED):
log.Println("✗ Command FAILED")
log.Printf(" Additional info: %d\n", resp.ResultParam2)

default:
log.Printf("✗ Unknown result: %d\n", resp.Result)
}

return
}
}
}
}
131 changes: 131 additions & 0 deletions node.go
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ import (
"time"

"github.com/bluenviron/gomavlib/v3/pkg/dialect"
"github.com/bluenviron/gomavlib/v3/pkg/dialects/common"
"github.com/bluenviron/gomavlib/v3/pkg/frame"
"github.com/bluenviron/gomavlib/v3/pkg/message"
)
Expand Down Expand Up @@ -183,6 +184,7 @@ type Node struct {
channels map[*Channel]struct{}
nodeHeartbeat *nodeHeartbeat
nodeStreamRequest *nodeStreamRequest
nodeCommand *nodeCommand

// in
chNewChannel chan *Channel
Expand Down Expand Up @@ -311,6 +313,18 @@ func (n *Node) Initialize() error {
}
}

n.nodeCommand = &nodeCommand{
node: n,
}
err = n.nodeCommand.initialize()
if err != nil {
if errors.Is(err, errSkip) {
n.nodeCommand = nil
} else {
return err
}
}

if n.nodeHeartbeat != nil {
go n.nodeHeartbeat.run()
}
Expand All @@ -319,6 +333,11 @@ func (n *Node) Initialize() error {
go n.nodeStreamRequest.run()
}

if n.nodeCommand != nil {
n.wg.Add(1)
go n.nodeCommand.run()
}

for ca := range n.channelProviders {
ca.start()
}
Expand Down Expand Up @@ -378,6 +397,10 @@ outer:
n.nodeStreamRequest.close()
}

if n.nodeCommand != nil {
n.nodeCommand.close()
}

for ca := range n.channelProviders {
ca.close()
}
Expand Down Expand Up @@ -576,6 +599,114 @@ func (n *Node) WriteFrameExcept(exceptChannel *Channel, fr frame.Frame) error {
return nil
}

// SendCommandLong sends a COMMAND_LONG and waits for COMMAND_ACK response.
func (n *Node) SendCommandLong(command *common.MessageCommandLong, options *CommandOptions) (*CommandResponse, error) {
if n.nodeCommand == nil {
return nil, fmt.Errorf("command manager not initialized (dialect required)")
}

if n.nodeCommand.msgCommandLong == nil {
return nil, fmt.Errorf("COMMAND_LONG not available in dialect")
}

return n.sendCommand(
command,
command.TargetSystem,
command.TargetComponent,
uint32(command.Command),
options,
)
}

// SendCommandInt sends a COMMAND_INT and waits for COMMAND_ACK response.
func (n *Node) SendCommandInt(command *common.MessageCommandInt, options *CommandOptions) (*CommandResponse, error) {
if n.nodeCommand == nil {
return nil, fmt.Errorf("command manager not initialized (dialect required)")
}

if n.nodeCommand.msgCommandInt == nil {
return nil, fmt.Errorf("COMMAND_INT not available in dialect")
}

return n.sendCommand(
command,
command.TargetSystem,
command.TargetComponent,
uint32(command.Command),
options,
)
}

// sendCommand is the internal unified command sender used by both
// SendCommandLong and SendCommandInt.
func (n *Node) sendCommand(
msg message.Message,
targetSystem uint8,
targetComponent uint8,
commandID uint32,
opts *CommandOptions,
) (*CommandResponse, error) {
if opts == nil {
return nil, fmt.Errorf("options is nil. Channel is required")
}
if opts.Channel == nil {
return nil, fmt.Errorf("need channel to send command on")
}
if opts.Timeout == 0 {
opts.Timeout = defaultCommandTimeout
}

req := &sendCommandReq{
channel: opts.Channel,
msg: msg,
targetSystem: targetSystem,
targetComp: targetComponent,
commandID: commandID,
timeout: opts.Timeout,
responseCh: make(chan *CommandResponse, 1),
errorCh: make(chan error, 1),
}

// Set up progress callback if provided
var progressWg sync.WaitGroup
if opts.OnProgress != nil {
req.progressCh = make(chan uint8, 10)
progressWg.Add(1)
go func() {
defer progressWg.Done()
for progress := range req.progressCh {
opts.OnProgress(progress)
}
}()
}

// Send request to command manager goroutine
select {
case n.nodeCommand.chRequest <- req:
case <-n.terminate:
return nil, ErrNodeTerminated
}

// Wait for send confirmation
if err := <-req.errorCh; err != nil {
if req.progressCh != nil {
close(req.progressCh)
progressWg.Wait()
}
return nil, fmt.Errorf("failed to send command: %w", err)
}

// BLOCK waiting for response (with timeout handled by command manager)
response := <-req.responseCh

// The progress channel gets closed and through that wg.Done() is called
// by the command manager when the command is completed
// times out or is cancelled.
progressWg.Wait()

return response, nil
}

func (n *Node) pushEvent(evt Event) {
select {
case n.chEvent <- evt:
Expand Down
Loading