diff --git a/pkg/dialects/all/enum_mav_cmd.go b/pkg/dialects/all/enum_mav_cmd.go index 39a7eb501..2ccc4b3dc 100644 --- a/pkg/dialects/all/enum_mav_cmd.go +++ b/pkg/dialects/all/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/all/enum_mav_mode_property.go b/pkg/dialects/all/enum_mav_mode_property.go new file mode 100644 index 000000000..a8c7096a4 --- /dev/null +++ b/pkg/dialects/all/enum_mav_mode_property.go @@ -0,0 +1,20 @@ +//autogenerated:yes +//nolint:revive,misspell,govet,lll,dupl,gocritic +package all + +import ( + "github.com/bluenviron/gomavlib/v2/pkg/dialects/development" +) + +// Mode properties. +type MAV_MODE_PROPERTY = development.MAV_MODE_PROPERTY + +const ( + // If set, this mode is an advanced mode. + // For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. + // A GCS can optionally use this flag to configure the UI for its intended users. + MAV_MODE_PROPERTY_ADVANCED MAV_MODE_PROPERTY = development.MAV_MODE_PROPERTY_ADVANCED + // If set, this mode should not be added to the list of selectable modes. + // The mode might still be selected by the FC directly (for example as part of a failsafe). + MAV_MODE_PROPERTY_NOT_USER_SELECTABLE MAV_MODE_PROPERTY = development.MAV_MODE_PROPERTY_NOT_USER_SELECTABLE +) diff --git a/pkg/dialects/all/enum_mav_result.go b/pkg/dialects/all/enum_mav_result.go index ff7a2d791..ec669f6ea 100644 --- a/pkg/dialects/all/enum_mav_result.go +++ b/pkg/dialects/all/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/all/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/all/message_gimbal_manager_set_pitchyaw.go index ce4b27eff..c42079dff 100644 --- a/pkg/dialects/all/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/all/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/ardupilotmega/enum_mav_cmd.go b/pkg/dialects/ardupilotmega/enum_mav_cmd.go index 23ee098da..28fd05054 100644 --- a/pkg/dialects/ardupilotmega/enum_mav_cmd.go +++ b/pkg/dialects/ardupilotmega/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/ardupilotmega/enum_mav_result.go b/pkg/dialects/ardupilotmega/enum_mav_result.go index e3158476b..1867da40d 100644 --- a/pkg/dialects/ardupilotmega/enum_mav_result.go +++ b/pkg/dialects/ardupilotmega/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/ardupilotmega/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/ardupilotmega/message_gimbal_manager_set_pitchyaw.go index 06371293d..5d82d0551 100644 --- a/pkg/dialects/ardupilotmega/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/ardupilotmega/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/asluav/enum_mav_cmd.go b/pkg/dialects/asluav/enum_mav_cmd.go index 684a71148..820e6e88e 100644 --- a/pkg/dialects/asluav/enum_mav_cmd.go +++ b/pkg/dialects/asluav/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/asluav/enum_mav_result.go b/pkg/dialects/asluav/enum_mav_result.go index a1aa84875..33f0f147d 100644 --- a/pkg/dialects/asluav/enum_mav_result.go +++ b/pkg/dialects/asluav/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/asluav/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/asluav/message_gimbal_manager_set_pitchyaw.go index 21ce4f0f5..736d4676a 100644 --- a/pkg/dialects/asluav/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/asluav/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/avssuas/enum_mav_cmd.go b/pkg/dialects/avssuas/enum_mav_cmd.go index ed22760c8..0f0132704 100644 --- a/pkg/dialects/avssuas/enum_mav_cmd.go +++ b/pkg/dialects/avssuas/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/avssuas/enum_mav_result.go b/pkg/dialects/avssuas/enum_mav_result.go index 136928edb..eca654617 100644 --- a/pkg/dialects/avssuas/enum_mav_result.go +++ b/pkg/dialects/avssuas/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/avssuas/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/avssuas/message_gimbal_manager_set_pitchyaw.go index d5bfb6d82..13d06399b 100644 --- a/pkg/dialects/avssuas/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/avssuas/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/common/enum_mav_cmd.go b/pkg/dialects/common/enum_mav_cmd.go index 43d0abb88..8d458dfb3 100644 --- a/pkg/dialects/common/enum_mav_cmd.go +++ b/pkg/dialects/common/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/common/enum_mav_result.go b/pkg/dialects/common/enum_mav_result.go index a4c9532e1..459d3c703 100644 --- a/pkg/dialects/common/enum_mav_result.go +++ b/pkg/dialects/common/enum_mav_result.go @@ -25,6 +25,10 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = 5 // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = 6 + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = 7 + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = 8 ) var labels_MAV_RESULT = map[MAV_RESULT]string{ @@ -35,6 +39,8 @@ var labels_MAV_RESULT = map[MAV_RESULT]string{ MAV_RESULT_FAILED: "MAV_RESULT_FAILED", MAV_RESULT_IN_PROGRESS: "MAV_RESULT_IN_PROGRESS", MAV_RESULT_CANCELLED: "MAV_RESULT_CANCELLED", + MAV_RESULT_COMMAND_LONG_ONLY: "MAV_RESULT_COMMAND_LONG_ONLY", + MAV_RESULT_COMMAND_INT_ONLY: "MAV_RESULT_COMMAND_INT_ONLY", } // MarshalText implements the encoding.TextMarshaler interface. diff --git a/pkg/dialects/common/message_command_ack.go b/pkg/dialects/common/message_command_ack.go index bb5d7aa36..ad3cf6b5f 100644 --- a/pkg/dialects/common/message_command_ack.go +++ b/pkg/dialects/common/message_command_ack.go @@ -8,9 +8,9 @@ type MessageCommandAck struct { Command MAV_CMD `mavenum:"uint16"` // Result of command. Result MAV_RESULT `mavenum:"uint8"` - // Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (UINT8_MAX if the progress is unknown). + // The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown. Progress uint8 `mavext:"true"` - // Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied. + // Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown"). ResultParam2 int32 `mavext:"true"` // System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. TargetSystem uint8 `mavext:"true"` diff --git a/pkg/dialects/common/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/common/message_gimbal_manager_set_pitchyaw.go index 20eef1587..1172aeb17 100644 --- a/pkg/dialects/common/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/common/message_gimbal_manager_set_pitchyaw.go @@ -2,7 +2,7 @@ //nolint:revive,misspell,govet,lll package common -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw struct { // System ID TargetSystem uint8 diff --git a/pkg/dialects/cubepilot/enum_mav_cmd.go b/pkg/dialects/cubepilot/enum_mav_cmd.go index 1f479b109..2bcdec324 100644 --- a/pkg/dialects/cubepilot/enum_mav_cmd.go +++ b/pkg/dialects/cubepilot/enum_mav_cmd.go @@ -252,7 +252,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = common.MAV_CMD_JUMP_TAG // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = common.MAV_CMD_DO_JUMP_TAG - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE diff --git a/pkg/dialects/cubepilot/enum_mav_result.go b/pkg/dialects/cubepilot/enum_mav_result.go index fd25f671c..c947c2101 100644 --- a/pkg/dialects/cubepilot/enum_mav_result.go +++ b/pkg/dialects/cubepilot/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/cubepilot/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/cubepilot/message_gimbal_manager_set_pitchyaw.go index b69b91e3b..8cb9a3ab4 100644 --- a/pkg/dialects/cubepilot/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/cubepilot/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/development/enum_mav_cmd.go b/pkg/dialects/development/enum_mav_cmd.go index df6750347..8258ea890 100644 --- a/pkg/dialects/development/enum_mav_cmd.go +++ b/pkg/dialects/development/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/development/enum_mav_mode_property.go b/pkg/dialects/development/enum_mav_mode_property.go new file mode 100644 index 000000000..6eb9cf208 --- /dev/null +++ b/pkg/dialects/development/enum_mav_mode_property.go @@ -0,0 +1,64 @@ +//autogenerated:yes +//nolint:revive,misspell,govet,lll,dupl,gocritic +package development + +import ( + "fmt" + "strings" +) + +// Mode properties. +type MAV_MODE_PROPERTY uint32 + +const ( + // If set, this mode is an advanced mode. + // For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. + // A GCS can optionally use this flag to configure the UI for its intended users. + MAV_MODE_PROPERTY_ADVANCED MAV_MODE_PROPERTY = 1 + // If set, this mode should not be added to the list of selectable modes. + // The mode might still be selected by the FC directly (for example as part of a failsafe). + MAV_MODE_PROPERTY_NOT_USER_SELECTABLE MAV_MODE_PROPERTY = 2 +) + +var labels_MAV_MODE_PROPERTY = map[MAV_MODE_PROPERTY]string{ + MAV_MODE_PROPERTY_ADVANCED: "MAV_MODE_PROPERTY_ADVANCED", + MAV_MODE_PROPERTY_NOT_USER_SELECTABLE: "MAV_MODE_PROPERTY_NOT_USER_SELECTABLE", +} + +// MarshalText implements the encoding.TextMarshaler interface. +func (e MAV_MODE_PROPERTY) MarshalText() ([]byte, error) { + var names []string + for mask, label := range labels_MAV_MODE_PROPERTY { + if e&mask == mask { + names = append(names, label) + } + } + return []byte(strings.Join(names, " | ")), nil +} + +// UnmarshalText implements the encoding.TextUnmarshaler interface. +func (e *MAV_MODE_PROPERTY) UnmarshalText(text []byte) error { + labels := strings.Split(string(text), " | ") + var mask MAV_MODE_PROPERTY + for _, label := range labels { + found := false + for value, l := range labels_MAV_MODE_PROPERTY { + if l == label { + mask |= value + found = true + break + } + } + if !found { + return fmt.Errorf("invalid label '%s'", label) + } + } + *e = mask + return nil +} + +// String implements the fmt.Stringer interface. +func (e MAV_MODE_PROPERTY) String() string { + val, _ := e.MarshalText() + return string(val) +} diff --git a/pkg/dialects/development/enum_mav_result.go b/pkg/dialects/development/enum_mav_result.go index d8b90df57..02308c9d5 100644 --- a/pkg/dialects/development/enum_mav_result.go +++ b/pkg/dialects/development/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/development/message_available_modes.go b/pkg/dialects/development/message_available_modes.go index 2a17acbf1..534b6fda2 100644 --- a/pkg/dialects/development/message_available_modes.go +++ b/pkg/dialects/development/message_available_modes.go @@ -14,12 +14,12 @@ type MessageAvailableModes struct { ModeIndex uint8 // Standard mode. StandardMode MAV_STANDARD_MODE `mavenum:"uint8"` - // System mode bitmap. - BaseMode MAV_MODE_FLAG `mavenum:"uint8"` // A bitfield for use for autopilot-specific flags CustomMode uint32 + // Mode properties. + Properties MAV_MODE_PROPERTY `mavenum:"uint32"` // Name of custom mode, with null termination character. Should be omitted for standard modes. - ModeName string `mavlen:"50"` + ModeName string `mavlen:"35"` } // GetID implements the message.Message interface. diff --git a/pkg/dialects/development/message_current_mode.go b/pkg/dialects/development/message_current_mode.go index bd1973df4..5d03188f9 100644 --- a/pkg/dialects/development/message_current_mode.go +++ b/pkg/dialects/development/message_current_mode.go @@ -8,10 +8,10 @@ package development type MessageCurrentMode struct { // Standard mode. StandardMode MAV_STANDARD_MODE `mavenum:"uint8"` - // System mode bitmap. - BaseMode MAV_MODE_FLAG `mavenum:"uint8"` // A bitfield for use for autopilot-specific flags CustomMode uint32 + // The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied + IntendedCustomMode uint32 } // GetID implements the message.Message interface. diff --git a/pkg/dialects/development/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/development/message_gimbal_manager_set_pitchyaw.go index a2ac0aa6b..bcb5fd2d1 100644 --- a/pkg/dialects/development/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/development/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/matrixpilot/enum_mav_cmd.go b/pkg/dialects/matrixpilot/enum_mav_cmd.go index aa25a6983..b0f94e34e 100644 --- a/pkg/dialects/matrixpilot/enum_mav_cmd.go +++ b/pkg/dialects/matrixpilot/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/matrixpilot/enum_mav_result.go b/pkg/dialects/matrixpilot/enum_mav_result.go index 89e161243..732e41a7b 100644 --- a/pkg/dialects/matrixpilot/enum_mav_result.go +++ b/pkg/dialects/matrixpilot/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/matrixpilot/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/matrixpilot/message_gimbal_manager_set_pitchyaw.go index a450ec832..ec1555036 100644 --- a/pkg/dialects/matrixpilot/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/matrixpilot/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/paparazzi/enum_mav_cmd.go b/pkg/dialects/paparazzi/enum_mav_cmd.go index 531c0f9c2..03e817788 100644 --- a/pkg/dialects/paparazzi/enum_mav_cmd.go +++ b/pkg/dialects/paparazzi/enum_mav_cmd.go @@ -252,7 +252,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = common.MAV_CMD_JUMP_TAG // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = common.MAV_CMD_DO_JUMP_TAG - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE diff --git a/pkg/dialects/paparazzi/enum_mav_result.go b/pkg/dialects/paparazzi/enum_mav_result.go index f3b9c4607..587f4fc6c 100644 --- a/pkg/dialects/paparazzi/enum_mav_result.go +++ b/pkg/dialects/paparazzi/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/paparazzi/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/paparazzi/message_gimbal_manager_set_pitchyaw.go index b9f315939..a1a277803 100644 --- a/pkg/dialects/paparazzi/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/paparazzi/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/pythonarraytest/enum_mav_cmd.go b/pkg/dialects/pythonarraytest/enum_mav_cmd.go index 9139e0989..43e33fa7d 100644 --- a/pkg/dialects/pythonarraytest/enum_mav_cmd.go +++ b/pkg/dialects/pythonarraytest/enum_mav_cmd.go @@ -252,7 +252,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = common.MAV_CMD_JUMP_TAG // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = common.MAV_CMD_DO_JUMP_TAG - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE diff --git a/pkg/dialects/pythonarraytest/enum_mav_result.go b/pkg/dialects/pythonarraytest/enum_mav_result.go index f4bd88a31..7b6cae04d 100644 --- a/pkg/dialects/pythonarraytest/enum_mav_result.go +++ b/pkg/dialects/pythonarraytest/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/pythonarraytest/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/pythonarraytest/message_gimbal_manager_set_pitchyaw.go index e0016164d..74ebaf373 100644 --- a/pkg/dialects/pythonarraytest/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/pythonarraytest/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/storm32/enum_mav_cmd.go b/pkg/dialects/storm32/enum_mav_cmd.go index 62590f65d..549f62c87 100644 --- a/pkg/dialects/storm32/enum_mav_cmd.go +++ b/pkg/dialects/storm32/enum_mav_cmd.go @@ -253,7 +253,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = 600 // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = 601 - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000 // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001 diff --git a/pkg/dialects/storm32/enum_mav_result.go b/pkg/dialects/storm32/enum_mav_result.go index c3856beaf..45d643257 100644 --- a/pkg/dialects/storm32/enum_mav_result.go +++ b/pkg/dialects/storm32/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/storm32/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/storm32/message_gimbal_manager_set_pitchyaw.go index 35429a535..7f67927ae 100644 --- a/pkg/dialects/storm32/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/storm32/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/ualberta/enum_mav_cmd.go b/pkg/dialects/ualberta/enum_mav_cmd.go index 6c22d9c4f..8bfbb4e70 100644 --- a/pkg/dialects/ualberta/enum_mav_cmd.go +++ b/pkg/dialects/ualberta/enum_mav_cmd.go @@ -252,7 +252,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = common.MAV_CMD_JUMP_TAG // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = common.MAV_CMD_DO_JUMP_TAG - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE diff --git a/pkg/dialects/ualberta/enum_mav_result.go b/pkg/dialects/ualberta/enum_mav_result.go index c4f0ccf27..856023eb0 100644 --- a/pkg/dialects/ualberta/enum_mav_result.go +++ b/pkg/dialects/ualberta/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/ualberta/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/ualberta/message_gimbal_manager_set_pitchyaw.go index 14ea1a861..026d930c8 100644 --- a/pkg/dialects/ualberta/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/ualberta/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw diff --git a/pkg/dialects/uavionix/enum_mav_cmd.go b/pkg/dialects/uavionix/enum_mav_cmd.go index 756ddd0ea..4d4210ef1 100644 --- a/pkg/dialects/uavionix/enum_mav_cmd.go +++ b/pkg/dialects/uavionix/enum_mav_cmd.go @@ -252,7 +252,7 @@ const ( MAV_CMD_JUMP_TAG MAV_CMD = common.MAV_CMD_JUMP_TAG // Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. MAV_CMD_DO_JUMP_TAG MAV_CMD = common.MAV_CMD_DO_JUMP_TAG - // High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. + // Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW // Gimbal configuration to set which sysid/compid is in primary and secondary control. MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = common.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE diff --git a/pkg/dialects/uavionix/enum_mav_result.go b/pkg/dialects/uavionix/enum_mav_result.go index 5cd4b0404..17332be6a 100644 --- a/pkg/dialects/uavionix/enum_mav_result.go +++ b/pkg/dialects/uavionix/enum_mav_result.go @@ -24,4 +24,8 @@ const ( MAV_RESULT_IN_PROGRESS MAV_RESULT = common.MAV_RESULT_IN_PROGRESS // Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). MAV_RESULT_CANCELLED MAV_RESULT = common.MAV_RESULT_CANCELLED + // Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). + MAV_RESULT_COMMAND_LONG_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_LONG_ONLY + // Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). + MAV_RESULT_COMMAND_INT_ONLY MAV_RESULT = common.MAV_RESULT_COMMAND_INT_ONLY ) diff --git a/pkg/dialects/uavionix/message_gimbal_manager_set_pitchyaw.go b/pkg/dialects/uavionix/message_gimbal_manager_set_pitchyaw.go index ed0298ee1..b8a25e9d0 100644 --- a/pkg/dialects/uavionix/message_gimbal_manager_set_pitchyaw.go +++ b/pkg/dialects/uavionix/message_gimbal_manager_set_pitchyaw.go @@ -6,5 +6,5 @@ import ( "github.com/bluenviron/gomavlib/v2/pkg/dialects/common" ) -// High level message to control a gimbal's pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. +// Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. type MessageGimbalManagerSetPitchyaw = common.MessageGimbalManagerSetPitchyaw