diff --git a/.cproject b/.cproject
index f90fe5d114..a0577f3329 100644
--- a/.cproject
+++ b/.cproject
@@ -77,7 +77,7 @@
-
+
diff --git a/msg/input_rc.msg b/msg/input_rc.msg
new file mode 100644
index 0000000000..c07d229503
--- /dev/null
+++ b/msg/input_rc.msg
@@ -0,0 +1,21 @@
+uint8 RC_INPUT_SOURCE_UNKNOWN = 0
+uint8 RC_INPUT_SOURCE_PX4FMU_PPM = 1
+uint8 RC_INPUT_SOURCE_PX4IO_PPM = 2
+uint8 RC_INPUT_SOURCE_PX4IO_SPEKTRUM = 3
+uint8 RC_INPUT_SOURCE_PX4IO_SBUS = 4
+uint8 RC_INPUT_SOURCE_PX4IO_ST24 = 5
+uint8 RC_INPUT_SOURCE_MAVLINK = 6
+
+uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels.
+
+uint64 timestamp_publication # publication time
+uint64 timestamp_last_signal # last valid reception time
+uint32 channel_count # number of channels actually being seen
+int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception
+bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly.
+bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss.
+uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality.
+uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality.
+uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems
+uint8 input_source # Input source
+uint16[18] values # measured pulse widths for each of the supported channels
diff --git a/msg/mission.msg b/msg/mission.msg
new file mode 100644
index 0000000000..ac135a4e09
--- /dev/null
+++ b/msg/mission.msg
@@ -0,0 +1,3 @@
+int32 dataman_id # default 0, there are two offboard storage places in the dataman: 0 or 1
+uint32 count # count of the missions stored in the dataman
+int32 current_seq # default -1, start at the one changed latest
diff --git a/msg/output_pwm.msg b/msg/output_pwm.msg
new file mode 100644
index 0000000000..1418a43e6e
--- /dev/null
+++ b/msg/output_pwm.msg
@@ -0,0 +1,3 @@
+uint8 PWM_OUTPUT_MAX_CHANNELS = 16
+uint16[16] values
+uint32 channel_count
diff --git a/msg/rc_parameter_map.msg b/msg/rc_parameter_map.msg
new file mode 100644
index 0000000000..b2dd1843ab
--- /dev/null
+++ b/msg/rc_parameter_map.msg
@@ -0,0 +1,11 @@
+uint8 RC_PARAM_MAP_NCHAN = 3 # This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h
+uint8 PARAM_ID_LEN = 16 # corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
+
+uint64 timestamp # time at which the map was updated
+bool[3] valid #true for RC-Param channels which are mapped to a param
+int32[3] param_index # corresponding param index, this field is ignored if set to -1, in this case param_id will be used
+char[51] param_id # MAP_NCHAN * (ID_LEN + 1) chars, corresponding param id, null terminated
+float32[3] scale # scale to map the RC input [-1, 1] to a parameter value
+float32[3] value0 # inital value around which the parameter value is changed
+float32[3] value_min # minimal parameter value
+float32[3] value_max # minimal parameter value
diff --git a/msg/sensor_accel.msg b/msg/sensor_accel.msg
new file mode 100644
index 0000000000..fdae381aba
--- /dev/null
+++ b/msg/sensor_accel.msg
@@ -0,0 +1,13 @@
+uint64 timestamp
+uint64 error_count
+float32 x # acceleration in the NED X board axis in m/s^2
+float32 y # acceleration in the NED Y board axis in m/s^2
+float32 z # acceleration in the NED Z board axis in m/s^2
+float32 temperature # temperature in degrees celsius
+float32 range_m_s2 # range in m/s^2 (+- this value)
+float32 scaling
+
+int16 x_raw
+int16 y_raw
+int16 z_raw
+int16 temperature_raw
diff --git a/msg/sensor_baro.msg b/msg/sensor_baro.msg
new file mode 100644
index 0000000000..315d5a56ec
--- /dev/null
+++ b/msg/sensor_baro.msg
@@ -0,0 +1,5 @@
+float32 pressure
+float32 altitude
+float32 temperature
+uint64 timestamp
+uint64 error_count
diff --git a/msg/sensor_gyro.msg b/msg/sensor_gyro.msg
new file mode 100644
index 0000000000..4a252269e8
--- /dev/null
+++ b/msg/sensor_gyro.msg
@@ -0,0 +1,13 @@
+uint64 timestamp
+uint64 error_count
+float32 x # angular velocity in the NED X board axis in rad/s
+float32 y # angular velocity in the NED Y board axis in rad/s
+float32 z # angular velocity in the NED Z board axis in rad/s
+float32 temperature # temperature in degrees celcius
+float32 range_rad_s
+float32 scaling
+
+int16 x_raw
+int16 y_raw
+int16 z_raw
+int16 temperature_raw
diff --git a/msg/sensor_mag.msg b/msg/sensor_mag.msg
new file mode 100644
index 0000000000..3ac97227ea
--- /dev/null
+++ b/msg/sensor_mag.msg
@@ -0,0 +1,12 @@
+uint64 timestamp
+uint64 error_count
+float32 x
+float32 y
+float32 z
+float32 range_ga
+float32 scaling
+float32 temperature
+
+int16 x_raw
+int16 y_raw
+int16 z_raw
diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h
index 738b28a6e1..3af204edcd 100644
--- a/src/drivers/drv_accel.h
+++ b/src/drivers/drv_accel.h
@@ -51,25 +51,8 @@
#define ACCEL1_DEVICE_PATH "/dev/accel1"
#define ACCEL2_DEVICE_PATH "/dev/accel2"
-/**
- * accel report structure. Reads from the device must be in multiples of this
- * structure.
- */
-struct accel_report {
- uint64_t timestamp;
- uint64_t error_count;
- float x; /**< acceleration in the NED X board axis in m/s^2 */
- float y; /**< acceleration in the NED Y board axis in m/s^2 */
- float z; /**< acceleration in the NED Z board axis in m/s^2 */
- float temperature; /**< temperature in degrees celsius */
- float range_m_s2; /**< range in m/s^2 (+- this value) */
- float scaling;
-
- int16_t x_raw;
- int16_t y_raw;
- int16_t z_raw;
- int16_t temperature_raw;
-};
+#include
+#define accel_report sensor_accel_s
/** accel scaling factors; Vout = Vscale * (Vin + Voffset) */
struct accel_scale {
@@ -81,11 +64,6 @@ struct accel_scale {
float z_scale;
};
-/*
- * ObjDev tag for raw accelerometer data.
- */
-ORB_DECLARE(sensor_accel);
-
/*
* ioctl() definitions
*
diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h
index 791e3c5cc1..87bf1000ec 100644
--- a/src/drivers/drv_baro.h
+++ b/src/drivers/drv_baro.h
@@ -50,22 +50,8 @@
#define BARO_BASE_DEVICE_PATH "/dev/baro"
#define BARO0_DEVICE_PATH "/dev/baro0"
-/**
- * baro report structure. Reads from the device must be in multiples of this
- * structure.
- */
-struct baro_report {
- float pressure;
- float altitude;
- float temperature;
- uint64_t timestamp;
- uint64_t error_count;
-};
-
-/*
- * ObjDev tag for raw barometer data.
- */
-ORB_DECLARE(sensor_baro);
+#include
+#define baro_report sensor_baro_s
/*
* ioctl() definitions
diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h
index 8e80413ac9..2ed65802cd 100644
--- a/src/drivers/drv_gyro.h
+++ b/src/drivers/drv_gyro.h
@@ -51,25 +51,8 @@
#define GYRO1_DEVICE_PATH "/dev/gyro1"
#define GYRO2_DEVICE_PATH "/dev/gyro2"
-/**
- * gyro report structure. Reads from the device must be in multiples of this
- * structure.
- */
-struct gyro_report {
- uint64_t timestamp;
- uint64_t error_count;
- float x; /**< angular velocity in the NED X board axis in rad/s */
- float y; /**< angular velocity in the NED Y board axis in rad/s */
- float z; /**< angular velocity in the NED Z board axis in rad/s */
- float temperature; /**< temperature in degrees celcius */
- float range_rad_s;
- float scaling;
-
- int16_t x_raw;
- int16_t y_raw;
- int16_t z_raw;
- int16_t temperature_raw;
-};
+#include
+#define gyro_report sensor_gyro_s
/** gyro scaling factors; Vout = (Vin * Vscale) + Voffset */
struct gyro_scale {
@@ -81,11 +64,6 @@ struct gyro_scale {
float z_scale;
};
-/*
- * ObjDev tag for raw gyro data.
- */
-ORB_DECLARE(sensor_gyro);
-
/*
* ioctl() definitions
*/
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index e2f8493e38..75d914de8e 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -49,26 +49,8 @@
#define MAG1_DEVICE_PATH "/dev/mag1"
#define MAG2_DEVICE_PATH "/dev/mag2"
-/**
- * mag report structure. Reads from the device must be in multiples of this
- * structure.
- *
- * Output values are in gauss.
- */
-struct mag_report {
- uint64_t timestamp;
- uint64_t error_count;
- float x;
- float y;
- float z;
- float range_ga;
- float scaling;
- float temperature;
-
- int16_t x_raw;
- int16_t y_raw;
- int16_t z_raw;
-};
+#include
+#define mag_report sensor_mag_s
/** mag scaling factors; Vout = (Vin * Vscale) + Voffset */
struct mag_scale {
@@ -80,12 +62,6 @@ struct mag_scale {
float z_scale;
};
-/*
- * ObjDev tag for raw magnetometer data.
- */
-ORB_DECLARE(sensor_mag);
-
-
/*
* ioctl() definitions
*/
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index eda113f5e4..fc619866be 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -61,10 +61,17 @@ __BEGIN_DECLS
#define PWM_OUTPUT_BASE_DEVICE_PATH "/dev/pwm_output"
#define PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0"
+#include
+#define pwm_output_values output_pwm_s
+
+#ifndef PWM_OUTPUT_MAX_CHANNELS
+ #define PWM_OUTPUT_MAX_CHANNELS output_pwm_s::PWM_OUTPUT_MAX_CHANNELS
+#endif
+
/**
* Maximum number of PWM output channels supported by the device.
*/
-#define PWM_OUTPUT_MAX_CHANNELS 16
+//#define PWM_OUTPUT_MAX_CHANNELS 16
/**
* Lowest minimum PWM in us
@@ -107,19 +114,6 @@ __BEGIN_DECLS
*/
typedef uint16_t servo_position_t;
-/**
- * Servo output status structure.
- *
- * May be published to output_pwm, or written to a PWM output
- * device.
- */
-struct pwm_output_values {
- /** desired pulse widths for each of the supported channels */
- servo_position_t values[PWM_OUTPUT_MAX_CHANNELS];
- unsigned channel_count;
-};
-
-
/**
* RC config values for a channel
*
@@ -136,11 +130,6 @@ struct pwm_output_rc_config {
bool rc_reverse;
};
-/*
- * ORB tag for PWM outputs.
- */
-ORB_DECLARE(output_pwm);
-
/*
* ioctl() definitions
*
diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h
index 63cfe9816a..90bad2f25d 100644
--- a/src/drivers/drv_px4flow.h
+++ b/src/drivers/drv_px4flow.h
@@ -46,11 +46,6 @@
#define PX4FLOW0_DEVICE_PATH "/dev/px4flow0"
-/*
- * ObjDev tag for px4flow data.
- */
-ORB_DECLARE(optical_flow);
-
/*
* ioctl() definitions
*
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index 725835cc0a..7d27c7f33a 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -48,11 +48,6 @@
#define RANGE_FINDER0_DEVICE_PATH "/dev/range_finder0"
#define MB12XX_MAX_RANGEFINDERS 12 // Maximum number of Maxbotix sensors on bus
-/*
- * ObjDev tag for distance sensor data.
- */
-ORB_DECLARE(distance_sensor);
-
/*
* ioctl() definitions
*
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index b82ced3845..b08f10d465 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -57,11 +57,6 @@
*/
#define RC_INPUT0_DEVICE_PATH "/dev/input_rc0"
-/**
- * Maximum number of R/C input channels in the system. S.Bus has up to 18 channels.
- */
-#define RC_INPUT_MAX_CHANNELS 18
-
/**
* Maximum RSSI value
*/
@@ -82,10 +77,9 @@
*/
#define RC_INPUT_MAX_DEADZONE_US 500
-/**
- * @addtogroup topics
- * @{
- */
+#include
+#define pwm_output_values output_pwm_s
+#define rc_input_values input_rc_s
/**
* Input signal type, value is a control position from zero to 100
@@ -93,85 +87,6 @@
*/
typedef uint16_t rc_input_t;
-enum RC_INPUT_SOURCE {
- RC_INPUT_SOURCE_UNKNOWN = 0,
- RC_INPUT_SOURCE_PX4FMU_PPM,
- RC_INPUT_SOURCE_PX4IO_PPM,
- RC_INPUT_SOURCE_PX4IO_SPEKTRUM,
- RC_INPUT_SOURCE_PX4IO_SBUS,
- RC_INPUT_SOURCE_PX4IO_ST24,
- RC_INPUT_SOURCE_MAVLINK
-};
-
-/**
- * R/C input status structure.
- *
- * Published to input_rc, may also be published to other names depending
- * on the board involved.
- */
-struct rc_input_values {
- /** publication time */
- uint64_t timestamp_publication;
-
- /** last valid reception time */
- uint64_t timestamp_last_signal;
-
- /** number of channels actually being seen */
- uint32_t channel_count;
-
- /** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception */
- int32_t rssi;
-
- /**
- * explicit failsafe flag: true on TX failure or TX out of range , false otherwise.
- * Only the true state is reliable, as there are some (PPM) receivers on the market going
- * into failsafe without telling us explicitly.
- * */
- bool rc_failsafe;
-
- /**
- * RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise.
- * True usally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems.
- * Will remain false, if a RX with failsafe option continues to transmit frames after a link loss.
- * */
- bool rc_lost;
-
- /**
- * Number of lost RC frames.
- * Note: intended purpose: observe the radio link quality if RSSI is not available
- * This value must not be used to trigger any failsafe-alike funtionality.
- * */
- uint16_t rc_lost_frame_count;
-
- /**
- * Number of total RC frames.
- * Note: intended purpose: observe the radio link quality if RSSI is not available
- * This value must not be used to trigger any failsafe-alike funtionality.
- * */
- uint16_t rc_total_frame_count;
-
- /**
- * Length of a single PPM frame.
- * Zero for non-PPM systems
- */
- uint16_t rc_ppm_frame_length;
-
- /** Input source */
- enum RC_INPUT_SOURCE input_source;
-
- /** measured pulse widths for each of the supported channels */
- rc_input_t values[RC_INPUT_MAX_CHANNELS];
-};
-
-/**
- * @}
- */
-
-/*
- * ObjDev tag for R/C inputs.
- */
-ORB_DECLARE(input_rc);
-
#define _RC_INPUT_BASE 0x2b00
/** Fetch R/C input values into (rc_input_values *)arg */
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 79a766fa5b..c1acccfaa1 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -607,7 +607,7 @@ PX4FMU::task_main()
orb_advert_t to_input_rc = 0;
memset(&rc_in, 0, sizeof(rc_in));
- rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM;
+ rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM;
#endif
/* initialize PWM limit lib */
@@ -772,8 +772,8 @@ PX4FMU::task_main()
// we have a new PPM frame. Publish it.
rc_in.channel_count = ppm_decoded_channels;
- if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) {
- rc_in.channel_count = RC_INPUT_MAX_CHANNELS;
+ if (rc_in.channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
+ rc_in.channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
}
for (uint8_t i = 0; i < rc_in.channel_count; i++) {
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index cdfce1e9c8..e53bdbd0a4 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -672,8 +672,8 @@ PX4IO::init()
return -1;
}
- if (_max_rc_input > RC_INPUT_MAX_CHANNELS)
- _max_rc_input = RC_INPUT_MAX_CHANNELS;
+ if (_max_rc_input > input_rc_s::RC_INPUT_MAX_CHANNELS)
+ _max_rc_input = input_rc_s::RC_INPUT_MAX_CHANNELS;
param_get(param_find("RC_RSSI_PWM_CHAN"), &_rssi_pwm_chan);
param_get(param_find("RC_RSSI_PWM_MAX"), &_rssi_pwm_max);
@@ -1675,10 +1675,10 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
int ret;
/* we don't have the status bits, so input_source has to be set elsewhere */
- input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
+ input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_UNKNOWN;
const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
- uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
+ uint16_t regs[input_rc_s::RC_INPUT_MAX_CHANNELS + prolog];
/*
* Read the channel count and the first 9 channels.
@@ -1697,8 +1697,8 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
channel_count = regs[PX4IO_P_RAW_RC_COUNT];
/* limit the channel count */
- if (channel_count > RC_INPUT_MAX_CHANNELS) {
- channel_count = RC_INPUT_MAX_CHANNELS;
+ if (channel_count > input_rc_s::RC_INPUT_MAX_CHANNELS) {
+ channel_count = input_rc_s::RC_INPUT_MAX_CHANNELS;
}
_rc_chan_count = channel_count;
@@ -1736,7 +1736,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
}
/* get RSSI from input channel */
- if (_rssi_pwm_chan > 0 && _rssi_pwm_chan <= RC_INPUT_MAX_CHANNELS && _rssi_pwm_max - _rssi_pwm_min != 0) {
+ if (_rssi_pwm_chan > 0 && _rssi_pwm_chan <= input_rc_s::RC_INPUT_MAX_CHANNELS && _rssi_pwm_max - _rssi_pwm_min != 0) {
int rssi = (input_rc.values[_rssi_pwm_chan - 1] - _rssi_pwm_min) /
((_rssi_pwm_max - _rssi_pwm_min) / 100);
rssi = rssi > 100 ? 100 : rssi;
@@ -1764,19 +1764,19 @@ PX4IO::io_publish_raw_rc()
/* sort out the source of the values */
if (_status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
- rc_val.input_source = RC_INPUT_SOURCE_PX4IO_PPM;
+ rc_val.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM;
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
- rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
+ rc_val.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
- rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+ rc_val.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_SBUS;
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_ST24) {
- rc_val.input_source = RC_INPUT_SOURCE_PX4IO_ST24;
+ rc_val.input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_ST24;
} else {
- rc_val.input_source = RC_INPUT_SOURCE_UNKNOWN;
+ rc_val.input_source = input_rc_s::RC_INPUT_SOURCE_UNKNOWN;
/* only keep publishing RC input if we ever got a valid input */
if (_rc_last_valid == 0) {
@@ -2660,19 +2660,19 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
/* sort out the source of the values */
if (status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_PPM;
+ rc_val->input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_PPM;
} else if (status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
+ rc_val->input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
} else if (status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+ rc_val->input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_SBUS;
} else if (status & PX4IO_P_STATUS_FLAGS_RC_ST24) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_ST24;
+ rc_val->input_source = input_rc_s::RC_INPUT_SOURCE_PX4IO_ST24;
} else {
- rc_val->input_source = RC_INPUT_SOURCE_UNKNOWN;
+ rc_val->input_source = input_rc_s::RC_INPUT_SOURCE_UNKNOWN;
}
/* read raw R/C input values */
@@ -2757,7 +2757,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
on param_get()
*/
struct pwm_output_rc_config* config = (struct pwm_output_rc_config*)arg;
- if (config->channel >= RC_INPUT_MAX_CHANNELS) {
+ if (config->channel >= input_rc_s::RC_INPUT_MAX_CHANNELS) {
/* fail with error */
return -E2BIG;
}
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 3fb69c7086..bac72a81ce 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -108,6 +108,7 @@
#include
#include
#include
+#include
#include "px4_custom_mode.h"
#include "commander_helper.h"
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
index ad8df4970b..7ea93b87e9 100644
--- a/src/modules/dataman/dataman.h
+++ b/src/modules/dataman/dataman.h
@@ -39,6 +39,7 @@
#ifndef _DATAMANAGER_H
#define _DATAMANAGER_H
+#include
#include
#include
diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp
index 3cf0323a05..2c1a3d88f6 100644
--- a/src/modules/mavlink/mavlink_mission.cpp
+++ b/src/modules/mavlink/mavlink_mission.cpp
@@ -49,6 +49,7 @@
#include
#include
+#include
#include
#include
diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp
index 559cf2c89c..414b7ee96f 100644
--- a/src/modules/mavlink/mavlink_parameters.cpp
+++ b/src/modules/mavlink/mavlink_parameters.cpp
@@ -159,9 +159,9 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
/* Copy values from msg to uorb using the parameter_rc_channel_index as index */
size_t i = map_rc.parameter_rc_channel_index;
_rc_param_map.param_index[i] = map_rc.param_index;
- strncpy(&(_rc_param_map.param_id[i][0]), map_rc.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
+ strncpy(&(_rc_param_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1)]), map_rc.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
/* enforce null termination */
- _rc_param_map.param_id[i][MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = '\0';
+ _rc_param_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1) + rc_parameter_map_s::PARAM_ID_LEN] = '\0';
_rc_param_map.scale[i] = map_rc.scale;
_rc_param_map.value0[i] = map_rc.param_value0;
_rc_param_map.value_min[i] = map_rc.param_value_min;
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 55c4597677..24d0940477 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -1050,7 +1050,7 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
rc.rc_lost_frame_count = 0;
rc.rc_total_frame_count = 1;
rc.rc_ppm_frame_length = 0;
- rc.input_source = RC_INPUT_SOURCE_MAVLINK;
+ rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
rc.rssi = RC_INPUT_RSSI_MAX;
/* channels */
@@ -1094,7 +1094,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
rc.rc_lost_frame_count = 0;
rc.rc_total_frame_count = 1;
rc.rc_ppm_frame_length = 0;
- rc.input_source = RC_INPUT_SOURCE_MAVLINK;
+ rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
rc.rssi = RC_INPUT_RSSI_MAX;
/* roll */
diff --git a/src/modules/navigator/datalinkloss.cpp b/src/modules/navigator/datalinkloss.cpp
index 7925809f12..9f26d05016 100644
--- a/src/modules/navigator/datalinkloss.cpp
+++ b/src/modules/navigator/datalinkloss.cpp
@@ -45,6 +45,7 @@
#include
#include
#include
+#include
#include
#include
diff --git a/src/modules/navigator/enginefailure.cpp b/src/modules/navigator/enginefailure.cpp
index b0130a1f5c..0c344bff92 100644
--- a/src/modules/navigator/enginefailure.cpp
+++ b/src/modules/navigator/enginefailure.cpp
@@ -44,6 +44,7 @@
#include
#include
#include
+#include
#include
#include
diff --git a/src/modules/navigator/gpsfailure.cpp b/src/modules/navigator/gpsfailure.cpp
index 0ca69f0f75..e6097c87f3 100644
--- a/src/modules/navigator/gpsfailure.cpp
+++ b/src/modules/navigator/gpsfailure.cpp
@@ -45,6 +45,7 @@
#include
#include
#include
+#include
#include
#include
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
index de34797aa3..c988faab7d 100644
--- a/src/modules/navigator/mission.cpp
+++ b/src/modules/navigator/mission.cpp
@@ -55,6 +55,7 @@
#include
#include
#include
+#include
#include
#include
diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h
index c850a0313c..eb17a329ee 100644
--- a/src/modules/navigator/mission_block.h
+++ b/src/modules/navigator/mission_block.h
@@ -43,6 +43,8 @@
#include
+#include
+
#include
#include
#include
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/navigator/navigation.h
similarity index 89%
rename from src/modules/uORB/topics/mission.h
rename to src/modules/navigator/navigation.h
index 7363e7d968..d23a20c5ff 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/navigator/navigation.h
@@ -32,19 +32,18 @@
****************************************************************************/
/**
- * @file mission.h
+ * @file navigation.h
* Definition of a mission consisting of mission items.
* @author Thomas Gubler
* @author Julian Oes
* @author Lorenz Meier
*/
-#ifndef TOPIC_MISSION_H_
-#define TOPIC_MISSION_H_
+#ifndef NAVIGATION_H_
+#define NAVIGATION_H_
#include
#include
-#include "../uORB.h"
#define NUM_MISSIONS_SUPPORTED 256
@@ -103,15 +102,7 @@ struct mission_item_s {
int actuator_value; /**< new value for selected actuator in ms 900...2000 */
};
-/**
- * This topic used to notify navigator about mission changes, mission itself and new mission state
- * must be stored in dataman before publication.
- */
-struct mission_s {
- int dataman_id; /**< default 0, there are two offboard storage places in the dataman: 0 or 1 */
- unsigned count; /**< count of the missions stored in the dataman */
- int current_seq; /**< default -1, start at the one changed latest */
-};
+#include
/**
* @}
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
index 093e1be3c2..1ddedddff4 100644
--- a/src/modules/navigator/navigator.h
+++ b/src/modules/navigator/navigator.h
@@ -45,6 +45,7 @@
#include
#include
+#include
#include
#include
diff --git a/src/modules/navigator/rcloss.cpp b/src/modules/navigator/rcloss.cpp
index 40bf7f0223..fcc00148f8 100644
--- a/src/modules/navigator/rcloss.cpp
+++ b/src/modules/navigator/rcloss.cpp
@@ -47,7 +47,7 @@
#include
#include
-#include
+#include
#include
#include "navigator.h"
diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp
index b75b7fa221..246007ad81 100644
--- a/src/modules/navigator/rtl.cpp
+++ b/src/modules/navigator/rtl.cpp
@@ -47,7 +47,7 @@
#include
#include
-#include
+#include
#include
#include "navigator.h"
diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h
index 5928f1f07b..3506065802 100644
--- a/src/modules/navigator/rtl.h
+++ b/src/modules/navigator/rtl.h
@@ -44,8 +44,7 @@
#include
#include
-#include
-#include
+#include
#include
#include
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 274f10c3e9..cd5db542d3 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -165,7 +165,7 @@ public:
int start();
private:
- static const unsigned _rc_max_chan_count = RC_INPUT_MAX_CHANNELS; /**< maximum number of r/c channels we handle */
+ static const unsigned _rc_max_chan_count = input_rc_s::RC_INPUT_MAX_CHANNELS; /**< maximum number of r/c channels we handle */
/**
* Get and limit value for specified RC function. Returns NAN if not mapped.
@@ -249,7 +249,7 @@ private:
struct differential_pressure_s _diff_pres;
struct airspeed_s _airspeed;
struct rc_parameter_map_s _rc_parameter_map;
- float _param_rc_values[RC_PARAM_MAP_NCHAN]; /**< parameter values for RC control */
+ float _param_rc_values[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< parameter values for RC control */
math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
math::Matrix<3, 3> _mag_rotation[3]; /**< rotation matrix for the orientation that the external mag0 is mounted */
@@ -294,7 +294,7 @@ private:
int rc_map_aux4;
int rc_map_aux5;
- int rc_map_param[RC_PARAM_MAP_NCHAN];
+ int rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
int32_t rc_fails_thr;
float rc_assist_th;
@@ -350,8 +350,8 @@ private:
param_t rc_map_aux4;
param_t rc_map_aux5;
- param_t rc_map_param[RC_PARAM_MAP_NCHAN];
- param_t rc_param[RC_PARAM_MAP_NCHAN]; /**< param handles for the paramters which are bound
+ param_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
+ param_t rc_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< param handles for the paramters which are bound
to a RC channel, equivalent float values in the
_parameters struct are not existing
because these parameters are never read. */
@@ -603,9 +603,9 @@ Sensors::Sensors() :
_parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
/* RC to parameter mapping for changing parameters with RC */
- for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
- char name[PARAM_ID_LEN];
- snprintf(name, PARAM_ID_LEN, "RC_MAP_PARAM%d", i + 1); // shifted by 1 because param name starts at 1
+ for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
+ char name[rc_parameter_map_s::PARAM_ID_LEN];
+ snprintf(name, rc_parameter_map_s::PARAM_ID_LEN, "RC_MAP_PARAM%d", i + 1); // shifted by 1 because param name starts at 1
_parameter_handles.rc_map_param[i] = param_find(name);
}
@@ -783,7 +783,7 @@ Sensors::parameters_update()
param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
- for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
param_get(_parameter_handles.rc_map_param[i], &(_parameters.rc_map_param[i]));
}
@@ -831,7 +831,7 @@ Sensors::parameters_update()
_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_AUX_4] = _parameters.rc_map_aux4 - 1;
_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_AUX_5] = _parameters.rc_map_aux5 - 1;
- for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_PARAM_1 + i] = _parameters.rc_map_param[i] - 1;
}
@@ -1678,7 +1678,7 @@ Sensors::rc_parameter_map_poll(bool forced)
orb_copy(ORB_ID(rc_parameter_map), _rc_parameter_map_sub, &_rc_parameter_map);
/* update paramter handles to which the RC channels are mapped */
- for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
if (_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_PARAM_1 + i] < 0 || !_rc_parameter_map.valid[i]) {
/* This RC channel is not mapped to a RC-Parameter Channel (e.g. RC_MAP_PARAM1 == 0)
* or no request to map this channel to a param has been sent via mavlink
@@ -1691,17 +1691,17 @@ Sensors::rc_parameter_map_poll(bool forced)
_parameter_handles.rc_param[i] = param_for_used_index((unsigned)_rc_parameter_map.param_index[i]);
} else {
- _parameter_handles.rc_param[i] = param_find(_rc_parameter_map.param_id[i]);
+ _parameter_handles.rc_param[i] = param_find(&_rc_parameter_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1)]);
}
}
warnx("rc to parameter map updated");
- for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
warnx("\ti %d param_id %s scale %.3f value0 %.3f, min %.3f, max %.3f",
i,
- _rc_parameter_map.param_id[i],
+ &_rc_parameter_map.param_id[i * (rc_parameter_map_s::PARAM_ID_LEN + 1)],
(double)_rc_parameter_map.scale[i],
(double)_rc_parameter_map.value0[i],
(double)_rc_parameter_map.value_min[i],
@@ -1893,7 +1893,7 @@ Sensors::get_rc_sw2pos_position(uint8_t func, float on_th, bool on_inv)
void
Sensors::set_params_from_rc()
{
- for (int i = 0; i < RC_PARAM_MAP_NCHAN; i++) {
+ for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
if (_rc.function[rc_channels_s::RC_CHANNELS_FUNCTION_PARAM_1 + i] < 0 || !_rc_parameter_map.valid[i]) {
/* This RC channel is not mapped to a RC-Parameter Channel (e.g. RC_MAP_PARAM1 == 0)
* or no request to map this channel to a param has been sent via mavlink
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index df56e931ca..ac98048771 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -45,23 +45,23 @@
#include
-#include
-ORB_DEFINE(sensor_mag, struct mag_report);
+#include "topics/sensor_mag.h"
+ORB_DEFINE(sensor_mag, struct sensor_mag_s);
-#include
-ORB_DEFINE(sensor_accel, struct accel_report);
+#include "topics/sensor_accel.h"
+ORB_DEFINE(sensor_accel, struct sensor_accel_s);
-#include
-ORB_DEFINE(sensor_gyro, struct gyro_report);
+#include "topics/sensor_gyro.h"
+ORB_DEFINE(sensor_gyro, struct sensor_gyro_s);
-#include
-ORB_DEFINE(sensor_baro, struct baro_report);
+#include "topics/sensor_baro.h"
+ORB_DEFINE(sensor_baro, struct sensor_baro_s);
-#include
-ORB_DEFINE(output_pwm, struct pwm_output_values);
+#include "topics/output_pwm.h"
+ORB_DEFINE(output_pwm, struct output_pwm_s);
-#include
-ORB_DEFINE(input_rc, struct rc_input_values);
+#include "topics/input_rc.h"
+ORB_DEFINE(input_rc, struct input_rc_s);
#include "topics/pwm_input.h"
ORB_DEFINE(pwm_input, struct pwm_input_s);
@@ -140,6 +140,10 @@ ORB_DEFINE(position_setpoint_triplet, struct position_setpoint_triplet_s);
ORB_DEFINE(vehicle_global_velocity_setpoint, struct vehicle_global_velocity_setpoint_s);
#include "topics/mission.h"
+ORB_DEFINE(mission, struct mission_s);
+// XXX onboard and offboard mission are still declared here until this is
+// generator supported
+#include
ORB_DEFINE(offboard_mission, struct mission_s);
ORB_DEFINE(onboard_mission, struct mission_s);
diff --git a/src/modules/uORB/topics/rc_parameter_map.h b/src/modules/uORB/topics/rc_parameter_map.h
deleted file mode 100644
index 6e68dc4b6f..0000000000
--- a/src/modules/uORB/topics/rc_parameter_map.h
+++ /dev/null
@@ -1,76 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2014 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT ,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file rc_parameter_map.h
- * Maps RC channels to parameters
- *
- * @author Thomas Gubler
- */
-
-#ifndef TOPIC_RC_PARAMETER_MAP_H
-#define TOPIC_RC_PARAMETER_MAP_H
-
-#include
-#include "../uORB.h"
-
-#define RC_PARAM_MAP_NCHAN 3 // This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h
-#define PARAM_ID_LEN 16 // corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
-
-/**
- * @addtogroup topics
- * @{
- */
-
-struct rc_parameter_map_s {
- uint64_t timestamp; /**< time at which the map was updated */
-
- bool valid[RC_PARAM_MAP_NCHAN]; /**< true for RC-Param channels which are mapped to a param */
-
- int param_index[RC_PARAM_MAP_NCHAN]; /**< corresponding param index, this
- this field is ignored if set to -1, in this case param_id will
- be used*/
- char param_id[RC_PARAM_MAP_NCHAN][PARAM_ID_LEN + 1]; /**< corresponding param id, null terminated */
- float scale[RC_PARAM_MAP_NCHAN]; /** scale to map the RC input [-1, 1] to a parameter value */
- float value0[RC_PARAM_MAP_NCHAN]; /** inital value around which the parameter value is changed */
- float value_min[RC_PARAM_MAP_NCHAN]; /** minimal parameter value */
- float value_max[RC_PARAM_MAP_NCHAN]; /** minimal parameter value */
-};
-
-/**
- * @}
- */
-
-ORB_DECLARE(rc_parameter_map);
-
-#endif