github.com/bluenviron/gomavlib/v2@v2.2.1-0.20240308101627-2c07e3da629c/pkg/dialects/common/message_command_long.go (about)

     1  //autogenerated:yes
     2  //nolint:revive,misspell,govet,lll
     3  package common
     4  
     5  // Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at https://mavlink.io/en/services/command.html
     6  type MessageCommandLong struct {
     7  	// System which should execute the command
     8  	TargetSystem uint8
     9  	// Component which should execute the command, 0 for all components
    10  	TargetComponent uint8
    11  	// Command ID (of command to send).
    12  	Command MAV_CMD `mavenum:"uint16"`
    13  	// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
    14  	Confirmation uint8
    15  	// Parameter 1 (for the specific command).
    16  	Param1 float32
    17  	// Parameter 2 (for the specific command).
    18  	Param2 float32
    19  	// Parameter 3 (for the specific command).
    20  	Param3 float32
    21  	// Parameter 4 (for the specific command).
    22  	Param4 float32
    23  	// Parameter 5 (for the specific command).
    24  	Param5 float32
    25  	// Parameter 6 (for the specific command).
    26  	Param6 float32
    27  	// Parameter 7 (for the specific command).
    28  	Param7 float32
    29  }
    30  
    31  // GetID implements the message.Message interface.
    32  func (*MessageCommandLong) GetID() uint32 {
    33  	return 76
    34  }