aboutsummaryrefslogtreecommitdiff
path: root/apps/px4io/protocol.h
diff options
context:
space:
mode:
Diffstat (limited to 'apps/px4io/protocol.h')
-rw-r--r--apps/px4io/protocol.h64
1 files changed, 3 insertions, 61 deletions
diff --git a/apps/px4io/protocol.h b/apps/px4io/protocol.h
index 4cb8a54ef..682348a60 100644
--- a/apps/px4io/protocol.h
+++ b/apps/px4io/protocol.h
@@ -139,6 +139,7 @@
#define PX4IO_P_SETUP_ARMING 1 /* arming controls */
#define PX4IO_P_SETUP_ARMING_ARM_OK (1 << 0) /* OK to arm */
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE (1 << 2) /* request switch to manual override */
+#define PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK (1 << 3)
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
@@ -165,65 +166,6 @@
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1)
#define PX4IO_P_RC_CONFIG_STRIDE 6 /* spacing between channel config data */
-/*
- * Old serial PX4FMU <-> PX4IO messaging protocol.
- *
- * This initial version of the protocol is very simple; each side transmits a
- * complete update with each frame. This avoids the sending of many small
- * messages and the corresponding complexity involved.
- */
-
-
-#define PX4IO_RELAY_CHANNELS 4
-
-#pragma pack(push, 1)
-
-/**
- * Periodic command from FMU to IO.
- */
-struct px4io_command {
- uint16_t f2i_magic;
-#define F2I_MAGIC 0x636d
-
- uint16_t servo_rate;
- uint16_t output_control[PX4IO_CONTROL_CHANNELS]; /**< PWM output rate in Hz */
- bool relay_state[PX4IO_RELAY_CHANNELS]; /**< relay states as requested by FMU */
- bool arm_ok; /**< FMU allows full arming */
- bool vector_flight_mode_ok; /**< FMU aquired a valid position lock, ready for pos control */
- bool manual_override_ok; /**< if true, IO performs a direct manual override */
-};
-
-/**
- * Periodic report from IO to FMU
- */
-struct px4io_report {
- uint16_t i2f_magic;
-#define I2F_MAGIC 0x7570
-
- uint16_t rc_channel[PX4IO_INPUT_CHANNELS];
- bool armed;
- uint8_t channel_count;
-
- uint16_t battery_mv;
- uint16_t adc_in;
- uint8_t overcurrent;
-};
-
-/**
- * As-needed config message from FMU to IO
- */
-struct px4io_config {
- uint16_t f2i_config_magic;
-#define F2I_CONFIG_MAGIC 0x6366
-
- uint8_t rc_map[4]; /**< channel ordering of roll, pitch, yaw, throttle */
- uint16_t rc_min[4]; /**< min value for each channel */
- uint16_t rc_trim[4]; /**< trim value for each channel */
- uint16_t rc_max[4]; /**< max value for each channel */
- int8_t rc_rev[4]; /**< rev value for each channel */
- uint16_t rc_dz[4]; /**< dz value for each channel */
-};
-
/**
* As-needed mixer data upload.
*
@@ -241,7 +183,7 @@ struct px4io_mixdata {
char text[0]; /* actual text size may vary */
};
-/* maximum size is limited by the HX frame size */
-#define F2I_MIXER_MAX_TEXT (HX_STREAM_MAX_FRAME - sizeof(struct px4io_mixdata))
+/* maximum size is limited by the link frame size XXX use config values to set this */
+#define F2I_MIXER_MAX_TEXT (64 - sizeof(struct px4io_mixdata))
#pragma pack(pop) \ No newline at end of file