Merge pull request #2732 from PX4/uorb_topics3

uORB topics: Moved all to auto-generated
This commit is contained in:
Lorenz Meier
2015-08-23 16:34:36 +02:00
37 changed files with 174 additions and 353 deletions
+1 -1
View File
@@ -77,7 +77,7 @@
</cconfiguration>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<project id="PX4-Firmware.null.714401899" name="PX4-Firmware"/>
<project id="PX4Firmware.null.2007659608" name="PX4Firmware"/>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/>
<storageModule moduleId="refreshScope" versionNumber="2">
+21
View File
@@ -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
+3
View File
@@ -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
+3
View File
@@ -0,0 +1,3 @@
uint8 PWM_OUTPUT_MAX_CHANNELS = 16
uint16[16] values
uint32 channel_count
+11
View File
@@ -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
+13
View File
@@ -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
+5
View File
@@ -0,0 +1,5 @@
float32 pressure
float32 altitude
float32 temperature
uint64 timestamp
uint64 error_count
+13
View File
@@ -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
+12
View File
@@ -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
+2 -24
View File
@@ -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 <uORB/topics/sensor_accel.h>
#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
*
+2 -16
View File
@@ -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 <uORB/topics/sensor_baro.h>
#define baro_report sensor_baro_s
/*
* ioctl() definitions
+2 -24
View File
@@ -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 <uORB/topics/sensor_gyro.h>
#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
*/
+2 -26
View File
@@ -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 <uORB/topics/sensor_mag.h>
#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
*/
+8 -19
View File
@@ -61,10 +61,17 @@ __BEGIN_DECLS
#define PWM_OUTPUT_BASE_DEVICE_PATH "/dev/pwm_output"
#define PWM_OUTPUT0_DEVICE_PATH "/dev/pwm_output0"
#include <uORB/topics/output_pwm.h>
#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
*
-5
View File
@@ -46,11 +46,6 @@
#define PX4FLOW0_DEVICE_PATH "/dev/px4flow0"
/*
* ObjDev tag for px4flow data.
*/
ORB_DECLARE(optical_flow);
/*
* ioctl() definitions
*
-5
View File
@@ -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
*
+3 -88
View File
@@ -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 <uORB/topics/input_rc.h>
#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 */
+3 -3
View File
@@ -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++) {
+18 -18
View File
@@ -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;
}
+1
View File
@@ -108,6 +108,7 @@
#include <geo/geo.h>
#include <systemlib/state_table.h>
#include <dataman/dataman.h>
#include <navigator/navigation.h>
#include "px4_custom_mode.h"
#include "commander_helper.h"
+1
View File
@@ -39,6 +39,7 @@
#ifndef _DATAMANAGER_H
#define _DATAMANAGER_H
#include <navigator/navigation.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/fence.h>
+1
View File
@@ -49,6 +49,7 @@
#include <drivers/drv_hrt.h>
#include <dataman/dataman.h>
#include <navigator/navigation.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
+2 -2
View File
@@ -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;
+2 -2
View File
@@ -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 */
+1
View File
@@ -45,6 +45,7 @@
#include <mavlink/mavlink_log.h>
#include <systemlib/err.h>
#include <geo/geo.h>
#include <navigator/navigation.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
+1
View File
@@ -44,6 +44,7 @@
#include <mavlink/mavlink_log.h>
#include <systemlib/err.h>
#include <geo/geo.h>
#include <navigator/navigation.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
+1
View File
@@ -45,6 +45,7 @@
#include <mavlink/mavlink_log.h>
#include <systemlib/err.h>
#include <geo/geo.h>
#include <navigator/navigation.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
+1
View File
@@ -55,6 +55,7 @@
#include <systemlib/err.h>
#include <geo/geo.h>
#include <lib/mathlib/mathlib.h>
#include <navigator/navigation.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
+2
View File
@@ -43,6 +43,8 @@
#include <drivers/drv_hrt.h>
#include <navigator/navigation.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/position_setpoint_triplet.h>
@@ -32,19 +32,18 @@
****************************************************************************/
/**
* @file mission.h
* @file navigation.h
* Definition of a mission consisting of mission items.
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_MISSION_H_
#define TOPIC_MISSION_H_
#ifndef NAVIGATION_H_
#define NAVIGATION_H_
#include <stdint.h>
#include <stdbool.h>
#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 <uORB/topics/mission.h>
/**
* @}
+1
View File
@@ -45,6 +45,7 @@
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
#include <navigator/navigation.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
+1 -1
View File
@@ -47,7 +47,7 @@
#include <geo/geo.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
#include <navigator/navigation.h>
#include <uORB/topics/home_position.h>
#include "navigator.h"
+1 -1
View File
@@ -47,7 +47,7 @@
#include <geo/geo.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
#include <navigator/navigation.h>
#include <uORB/topics/home_position.h>
#include "navigator.h"
+1 -2
View File
@@ -44,8 +44,7 @@
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission.h>
#include <navigator/navigation.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/vehicle_global_position.h>
+15 -15
View File
@@ -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
+16 -12
View File
@@ -45,23 +45,23 @@
#include <drivers/drv_orb_dev.h>
#include <drivers/drv_mag.h>
ORB_DEFINE(sensor_mag, struct mag_report);
#include "topics/sensor_mag.h"
ORB_DEFINE(sensor_mag, struct sensor_mag_s);
#include <drivers/drv_accel.h>
ORB_DEFINE(sensor_accel, struct accel_report);
#include "topics/sensor_accel.h"
ORB_DEFINE(sensor_accel, struct sensor_accel_s);
#include <drivers/drv_gyro.h>
ORB_DEFINE(sensor_gyro, struct gyro_report);
#include "topics/sensor_gyro.h"
ORB_DEFINE(sensor_gyro, struct sensor_gyro_s);
#include <drivers/drv_baro.h>
ORB_DEFINE(sensor_baro, struct baro_report);
#include "topics/sensor_baro.h"
ORB_DEFINE(sensor_baro, struct sensor_baro_s);
#include <drivers/drv_pwm_output.h>
ORB_DEFINE(output_pwm, struct pwm_output_values);
#include "topics/output_pwm.h"
ORB_DEFINE(output_pwm, struct output_pwm_s);
#include <drivers/drv_rc_input.h>
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 <navigator/navigation.h>
ORB_DEFINE(offboard_mission, struct mission_s);
ORB_DEFINE(onboard_mission, struct mission_s);
@@ -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 <thomasgubler@gmail.com>
*/
#ifndef TOPIC_RC_PARAMETER_MAP_H
#define TOPIC_RC_PARAMETER_MAP_H
#include <stdint.h>
#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