27 changed files with 293 additions and 682 deletions
@ -0,0 +1,8 @@
@@ -0,0 +1,8 @@
|
||||
# Filtered bottom flow in bodyframe. |
||||
uint64 timestamp # time of this estimate, in microseconds since system start |
||||
|
||||
float32 sumx # Integrated bodyframe x flow in meters |
||||
float32 sumy # Integrated bodyframe y flow in meters |
||||
|
||||
float32 vx # Flow bodyframe x speed, m/s |
||||
float32 vy # Flow bodyframe y Speed, m/s |
@ -0,0 +1,10 @@
@@ -0,0 +1,10 @@
|
||||
# GPS home position in WGS84 coordinates. |
||||
uint64 timestamp # Timestamp (microseconds since system boot) |
||||
|
||||
float64 lat # Latitude in degrees |
||||
float64 lon # Longitude in degrees |
||||
float32 alt # Altitude in meters (AMSL) |
||||
|
||||
float32 x # X coordinate in meters |
||||
float32 y # Y coordinate in meters |
||||
float32 z # Z coordinate in meters |
@ -0,0 +1,17 @@
@@ -0,0 +1,17 @@
|
||||
# Optical flow in NED body frame in SI units. |
||||
# @see http://en.wikipedia.org/wiki/International_System_of_Units |
||||
|
||||
uint64 timestamp # in microseconds since system start |
||||
uint8 sensor_id # id of the sensor emitting the flow value |
||||
float32 pixel_flow_x_integral # accumulated optical flow in radians around x axis |
||||
float32 pixel_flow_y_integral # accumulated optical flow in radians around y axis |
||||
float32 gyro_x_rate_integral # accumulated gyro value in radians around x axis |
||||
float32 gyro_y_rate_integral # accumulated gyro value in radians around y axis |
||||
float32 gyro_z_rate_integral # accumulated gyro value in radians around z axis |
||||
float32 ground_distance_m # Altitude / distance to ground in meters |
||||
uint32 integration_timespan # accumulation timespan in microseconds |
||||
uint32 time_since_last_sonar_update # time since last sonar update in microseconds |
||||
uint16 frame_count_since_last_readout # number of accumulated frames in timespan |
||||
int16 gyro_temperature # Temperature * 100 in centi-degrees Celsius |
||||
uint8 quality # Average of quality of accumulated frames, 0: bad quality, 255: maximum quality |
||||
|
@ -0,0 +1,13 @@
@@ -0,0 +1,13 @@
|
||||
int16 RANGE_FINDER_TYPE_LASER = 0 |
||||
|
||||
# range finder report structure. Reads from the device must be in multiples of this |
||||
# structure. |
||||
uint64 timestamp |
||||
uint64 error_count |
||||
uint16 type # type, following RANGE_FINDER_TYPE enum |
||||
float32 distance # in meters |
||||
float32 minimum_distance # minimum distance the sensor can measure |
||||
float32 maximum_distance # maximum distance the sensor can measure |
||||
uint8 valid # 1 == within sensor range, 0 = outside sensor range |
||||
float32[12] distance_vector # in meters length should match MB12XX_MAX_RANGEFINDERS |
||||
uint8 just_updated # number of the most recent measurement sensor |
@ -0,0 +1,100 @@
@@ -0,0 +1,100 @@
|
||||
# Definition of the sensor_combined uORB topic. |
||||
|
||||
int32 MAGNETOMETER_MODE_NORMAL = 0 |
||||
int32 MAGNETOMETER_MODE_POSITIVE_BIAS = 1 |
||||
int32 MAGNETOMETER_MODE_NEGATIVE_BIAS = 2 |
||||
|
||||
# Sensor readings in raw and SI-unit form. |
||||
# |
||||
# These values are read from the sensors. Raw values are in sensor-specific units, |
||||
# the scaled values are in SI-units, as visible from the ending of the variable |
||||
# or the comments. The use of the SI fields is in general advised, as these fields |
||||
# are scaled and offset-compensated where possible and do not change with board |
||||
# revisions and sensor updates. |
||||
# |
||||
# Actual data, this is specific to the type of data which is stored in this struct |
||||
# A line containing L0GME will be added by the Python logging code generator to the logged dataset. |
||||
# |
||||
# NOTE: Ordering of fields optimized to align to 32 bit / 4 bytes Change with consideration only |
||||
|
||||
uint64 timestamp # Timestamp in microseconds since boot, from gyro |
||||
# |
||||
int16[3] gyro_raw # Raw sensor values of angular velocity |
||||
float32[3] gyro_rad_s # Angular velocity in radian per seconds |
||||
uint32 gyro_errcount # Error counter for gyro 0 |
||||
float32 gyro_temp # Temperature of gyro 0 |
||||
|
||||
int16[3] accelerometer_raw # Raw acceleration in NED body frame |
||||
float32[3] accelerometer_m_s2 # Acceleration in NED body frame, in m/s^2 |
||||
int16 accelerometer_mode # Accelerometer measurement mode |
||||
float32 accelerometer_range_m_s2 # Accelerometer measurement range in m/s^2 |
||||
uint64 accelerometer_timestamp # Accelerometer timestamp |
||||
uint32 accelerometer_errcount # Error counter for accel 0 |
||||
float32 accelerometer_temp # Temperature of accel 0 |
||||
|
||||
int16[3] magnetometer_raw # Raw magnetic field in NED body frame |
||||
float32[3] magnetometer_ga # Magnetic field in NED body frame, in Gauss |
||||
int16 magnetometer_mode # Magnetometer measurement mode |
||||
float32 magnetometer_range_ga # measurement range in Gauss |
||||
float32 magnetometer_cuttoff_freq_hz # Internal analog low pass frequency of sensor |
||||
uint64 magnetometer_timestamp # Magnetometer timestamp |
||||
uint32 magnetometer_errcount # Error counter for mag 0 |
||||
float32 magnetometer_temp # Temperature of mag 0 |
||||
|
||||
int16[3] gyro1_raw # Raw sensor values of angular velocity |
||||
float32[3] gyro1_rad_s # Angular velocity in radian per seconds |
||||
uint64 gyro1_timestamp # Gyro timestamp |
||||
uint32 gyro1_errcount # Error counter for gyro 1 |
||||
float32 gyro1_temp # Temperature of gyro 1 |
||||
|
||||
int16[3] accelerometer1_raw # Raw acceleration in NED body frame |
||||
float32[3] accelerometer1_m_s2 # Acceleration in NED body frame, in m/s^2 |
||||
uint64 accelerometer1_timestamp # Accelerometer timestamp |
||||
uint32 accelerometer1_errcount # Error counter for accel 1 |
||||
float32 accelerometer1_temp # Temperature of accel 1 |
||||
|
||||
int16[3] magnetometer1_raw # Raw magnetic field in NED body frame |
||||
float32[3] magnetometer1_ga # Magnetic field in NED body frame, in Gauss |
||||
uint64 magnetometer1_timestamp # Magnetometer timestamp |
||||
uint32 magnetometer1_errcount # Error counter for mag 1 |
||||
float32 magnetometer1_temp # Temperature of mag 1 |
||||
|
||||
int16[3] gyro2_raw # Raw sensor values of angular velocity |
||||
float32[3] gyro2_rad_s # Angular velocity in radian per seconds |
||||
uint64 gyro2_timestamp # Gyro timestamp |
||||
uint32 gyro2_errcount # Error counter for gyro 1 |
||||
float32 gyro2_temp # Temperature of gyro 1 |
||||
|
||||
int16[3] accelerometer2_raw # Raw acceleration in NED body frame |
||||
float32[3] accelerometer2_m_s2 # Acceleration in NED body frame, in m/s^2 |
||||
uint64 accelerometer2_timestamp # Accelerometer timestamp |
||||
uint32 accelerometer2_errcount # Error counter for accel 2 |
||||
float32 accelerometer2_temp # Temperature of accel 2 |
||||
|
||||
int16[3] magnetometer2_raw # Raw magnetic field in NED body frame |
||||
float32[3] magnetometer2_ga # Magnetic field in NED body frame, in Gauss |
||||
uint64 magnetometer2_timestamp # Magnetometer timestamp |
||||
uint32 magnetometer2_errcount # Error counter for mag 2 |
||||
float32 magnetometer2_temp # Temperature of mag 2 |
||||
|
||||
float32 baro_pres_mbar # Barometric pressure, already temp. comp. |
||||
float32 baro_alt_meter # Altitude, already temp. comp. |
||||
float32 baro_temp_celcius # Temperature in degrees celsius |
||||
uint64 baro_timestamp # Barometer timestamp |
||||
|
||||
float32 baro1_pres_mbar # Barometric pressure, already temp. comp. |
||||
float32 baro1_alt_meter # Altitude, already temp. comp. |
||||
float32 baro1_temp_celcius # Temperature in degrees celsius |
||||
uint64 baro1_timestamp # Barometer timestamp |
||||
|
||||
float32[10] adc_voltage_v # ADC voltages of ADC Chan 10/11/12/13 or -1 |
||||
uint16[10] adc_mapping # Channel indices of each of these values |
||||
float32 mcu_temp_celcius # Internal temperature measurement of MCU |
||||
|
||||
float32 differential_pressure_pa # Airspeed sensor differential pressure |
||||
uint64 differential_pressure_timestamp # Last measurement timestamp |
||||
float32 differential_pressure_filtered_pa # Low pass filtered airspeed sensor differential pressure reading |
||||
|
||||
float32 differential_pressure1_pa # Airspeed sensor differential pressure |
||||
uint64 differential_pressure1_timestamp # Last measurement timestamp |
||||
float32 differential_pressure1_filtered_pa # Low pass filtered airspeed sensor differential pressure reading |
@ -0,0 +1,20 @@
@@ -0,0 +1,20 @@
|
||||
# Fused global position in WGS84. |
||||
# This struct contains global position estimation. It is not the raw GPS |
||||
# measurement (@see vehicle_gps_position). This topic is usually published by the position |
||||
# estimator, which will take more sources of information into account than just GPS, |
||||
# e.g. control inputs of the vehicle in a Kalman-filter implementation. |
||||
# |
||||
uint64 timestamp # Time of this estimate, in microseconds since system start |
||||
uint64 time_utc_usec # GPS UTC timestamp in microseconds |
||||
float64 lat # Latitude in degrees |
||||
float64 lon # Longitude in degrees |
||||
float32 alt # Altitude AMSL in meters |
||||
float32 vel_n # Ground north velocity, m/s |
||||
float32 vel_e # Ground east velocity, m/s |
||||
float32 vel_d # Ground downside velocity, m/s |
||||
float32 yaw # Yaw in radians -PI..+PI. |
||||
float32 eph # Standard deviation of position estimate horizontally |
||||
float32 epv # Standard deviation of position vertically |
||||
float32 terrain_alt # Terrain altitude in m, WGS84 |
||||
bool terrain_alt_valid # Terrain altitude estimate is valid |
||||
bool dead_reckoning # True if this position is estimated through dead-reckoning |
@ -0,0 +1,29 @@
@@ -0,0 +1,29 @@
|
||||
# GPS position in WGS84 coordinates. |
||||
uint64 timestamp_position # Timestamp for position information |
||||
int32 lat # Latitude in 1E-7 degrees |
||||
int32 lon # Longitude in 1E-7 degrees |
||||
int32 alt # Altitude in 1E-3 meters (millimeters) above MSL |
||||
|
||||
uint64 timestamp_variance |
||||
float32 s_variance_m_s # speed accuracy estimate m/s |
||||
float32 c_variance_rad # course accuracy estimate rad |
||||
uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. |
||||
|
||||
float32 eph # GPS HDOP horizontal dilution of position in m |
||||
float32 epv # GPS VDOP horizontal dilution of position in m |
||||
|
||||
int32 noise_per_ms # GPS noise per millisecond |
||||
int32 jamming_indicator # indicates jamming is occurring |
||||
|
||||
uint64 timestamp_velocity # Timestamp for velocity informations |
||||
float32 vel_m_s # GPS ground speed (m/s) |
||||
float32 vel_n_m_s # GPS ground speed in m/s |
||||
float32 vel_e_m_s # GPS ground speed in m/s |
||||
float32 vel_d_m_s # GPS ground speed in m/s |
||||
float32 cog_rad # Course over ground (NOT heading, but direction of movement) in rad, -PI..PI |
||||
bool vel_ned_valid # Flag to indicate if NED speed is valid |
||||
|
||||
uint64 timestamp_time # Timestamp for time information |
||||
uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 |
||||
|
||||
uint8 satellites_used # Number of satellites used |
@ -1,73 +0,0 @@
@@ -1,73 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. |
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch> |
||||
* Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* 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 filtered_bottom_flow.h |
||||
* Definition of the filtered bottom flow uORB topic. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_FILTERED_BOTTOM_FLOW_H_ |
||||
#define TOPIC_FILTERED_BOTTOM_FLOW_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Filtered bottom flow in bodyframe. |
||||
*/ |
||||
struct filtered_bottom_flow_s { |
||||
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */ |
||||
|
||||
float sumx; /**< Integrated bodyframe x flow in meters */ |
||||
float sumy; /**< Integrated bodyframe y flow in meters */ |
||||
|
||||
float vx; /**< Flow bodyframe x speed, m/s */ |
||||
float vy; /**< Flow bodyframe y Speed, m/s */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(filtered_bottom_flow); |
||||
|
||||
#endif |
@ -1,77 +0,0 @@
@@ -1,77 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. |
||||
* Author: Lorenz Meier <lm@inf.ethz.ch> |
||||
* Julian Oes <joes@student.ethz.ch> |
||||
* |
||||
* 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 home_position.h |
||||
* Definition of the home position uORB topic. |
||||
* |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* @author Julian Oes <joes@student.ethz.ch> |
||||
*/ |
||||
|
||||
#ifndef TOPIC_HOME_POSITION_H_ |
||||
#define TOPIC_HOME_POSITION_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* GPS home position in WGS84 coordinates. |
||||
*/ |
||||
struct home_position_s { |
||||
uint64_t timestamp; /**< Timestamp (microseconds since system boot) */ |
||||
|
||||
double lat; /**< Latitude in degrees */ |
||||
double lon; /**< Longitude in degrees */ |
||||
float alt; /**< Altitude in meters (AMSL) */ |
||||
|
||||
float x; /**< X coordinate in meters */ |
||||
float y; /**< Y coordinate in meters */ |
||||
float z; /**< Z coordinate in meters */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(home_position); |
||||
|
||||
#endif |
@ -1,84 +0,0 @@
@@ -1,84 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* 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 optical_flow.h |
||||
* Definition of the optical flow uORB topic. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_OPTICAL_FLOW_H_ |
||||
#define TOPIC_OPTICAL_FLOW_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
*/ |
||||
|
||||
/**
|
||||
* Optical flow in NED body frame in SI units. |
||||
* |
||||
* @see http://en.wikipedia.org/wiki/International_System_of_Units
|
||||
*/ |
||||
struct optical_flow_s { |
||||
|
||||
uint64_t timestamp; /**< in microseconds since system start */ |
||||
uint8_t sensor_id; /**< id of the sensor emitting the flow value */ |
||||
float pixel_flow_x_integral; /**< accumulated optical flow in radians around x axis */ |
||||
float pixel_flow_y_integral; /**< accumulated optical flow in radians around y axis */ |
||||
float gyro_x_rate_integral; /**< accumulated gyro value in radians around x axis */ |
||||
float gyro_y_rate_integral; /**< accumulated gyro value in radians around y axis */ |
||||
float gyro_z_rate_integral; /**< accumulated gyro value in radians around z axis */ |
||||
float ground_distance_m; /**< Altitude / distance to ground in meters */ |
||||
uint32_t integration_timespan; /**<accumulation timespan in microseconds */ |
||||
uint32_t time_since_last_sonar_update;/**< time since last sonar update in microseconds */ |
||||
uint16_t frame_count_since_last_readout;/**< number of accumulated frames in timespan */ |
||||
int16_t gyro_temperature;/**< Temperature * 100 in centi-degrees Celsius */ |
||||
uint8_t quality; /**< Average of quality of accumulated frames, 0: bad quality, 255: maximum quality */ |
||||
|
||||
|
||||
|
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(optical_flow); |
||||
|
||||
#endif |
@ -1,172 +0,0 @@
@@ -1,172 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012-2015 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 sensor_combined.h |
||||
* Definition of the sensor_combined uORB topic. |
||||
* |
||||
* @author Thomas Gubler <thomas@px4.io> |
||||
* @author Julian Oes <julian@px4.io> |
||||
* @author Lorenz Meier <lorenz@px4.io> |
||||
*/ |
||||
|
||||
#ifndef SENSOR_COMBINED_H_ |
||||
#define SENSOR_COMBINED_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include "../uORB.h" |
||||
|
||||
enum MAGNETOMETER_MODE { |
||||
MAGNETOMETER_MODE_NORMAL = 0, |
||||
MAGNETOMETER_MODE_POSITIVE_BIAS, |
||||
MAGNETOMETER_MODE_NEGATIVE_BIAS |
||||
}; |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Sensor readings in raw and SI-unit form. |
||||
* |
||||
* These values are read from the sensors. Raw values are in sensor-specific units, |
||||
* the scaled values are in SI-units, as visible from the ending of the variable |
||||
* or the comments. The use of the SI fields is in general advised, as these fields |
||||
* are scaled and offset-compensated where possible and do not change with board |
||||
* revisions and sensor updates. |
||||
* |
||||
*/ |
||||
struct sensor_combined_s { |
||||
|
||||
/*
|
||||
* Actual data, this is specific to the type of data which is stored in this struct |
||||
* A line containing L0GME will be added by the Python logging code generator to the |
||||
* logged dataset. |
||||
*/ |
||||
|
||||
/* NOTE: Ordering of fields optimized to align to 32 bit / 4 bytes Change with consideration only */ |
||||
|
||||
uint64_t timestamp; /**< Timestamp in microseconds since boot, from gyro */ |
||||
|
||||
int16_t gyro_raw[3]; /**< Raw sensor values of angular velocity */ |
||||
float gyro_rad_s[3]; /**< Angular velocity in radian per seconds */ |
||||
unsigned gyro_errcount; /**< Error counter for gyro 0 */ |
||||
float gyro_temp; /**< Temperature of gyro 0 */ |
||||
|
||||
int16_t accelerometer_raw[3]; /**< Raw acceleration in NED body frame */ |
||||
float accelerometer_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */ |
||||
int accelerometer_mode; /**< Accelerometer measurement mode */ |
||||
float accelerometer_range_m_s2; /**< Accelerometer measurement range in m/s^2 */ |
||||
uint64_t accelerometer_timestamp; /**< Accelerometer timestamp */ |
||||
unsigned accelerometer_errcount; /**< Error counter for accel 0 */ |
||||
float accelerometer_temp; /**< Temperature of accel 0 */ |
||||
|
||||
int16_t magnetometer_raw[3]; /**< Raw magnetic field in NED body frame */ |
||||
float magnetometer_ga[3]; /**< Magnetic field in NED body frame, in Gauss */ |
||||
int magnetometer_mode; /**< Magnetometer measurement mode */ |
||||
float magnetometer_range_ga; /**< ± measurement range in Gauss */ |
||||
float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */ |
||||
uint64_t magnetometer_timestamp; /**< Magnetometer timestamp */ |
||||
unsigned magnetometer_errcount; /**< Error counter for mag 0 */ |
||||
float magnetometer_temp; /**< Temperature of mag 0 */ |
||||
|
||||
int16_t gyro1_raw[3]; /**< Raw sensor values of angular velocity */ |
||||
float gyro1_rad_s[3]; /**< Angular velocity in radian per seconds */ |
||||
uint64_t gyro1_timestamp; /**< Gyro timestamp */ |
||||
unsigned gyro1_errcount; /**< Error counter for gyro 1 */ |
||||
float gyro1_temp; /**< Temperature of gyro 1 */ |
||||
|
||||
int16_t accelerometer1_raw[3]; /**< Raw acceleration in NED body frame */ |
||||
float accelerometer1_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */ |
||||
uint64_t accelerometer1_timestamp; /**< Accelerometer timestamp */ |
||||
unsigned accelerometer1_errcount; /**< Error counter for accel 1 */ |
||||
float accelerometer1_temp; /**< Temperature of accel 1 */ |
||||
|
||||
int16_t magnetometer1_raw[3]; /**< Raw magnetic field in NED body frame */ |
||||
float magnetometer1_ga[3]; /**< Magnetic field in NED body frame, in Gauss */ |
||||
uint64_t magnetometer1_timestamp; /**< Magnetometer timestamp */ |
||||
unsigned magnetometer1_errcount; /**< Error counter for mag 1 */ |
||||
float magnetometer1_temp; /**< Temperature of mag 1 */ |
||||
|
||||
int16_t gyro2_raw[3]; /**< Raw sensor values of angular velocity */ |
||||
float gyro2_rad_s[3]; /**< Angular velocity in radian per seconds */ |
||||
uint64_t gyro2_timestamp; /**< Gyro timestamp */ |
||||
unsigned gyro2_errcount; /**< Error counter for gyro 1 */ |
||||
float gyro2_temp; /**< Temperature of gyro 1 */ |
||||
|
||||
int16_t accelerometer2_raw[3]; /**< Raw acceleration in NED body frame */ |
||||
float accelerometer2_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */ |
||||
uint64_t accelerometer2_timestamp; /**< Accelerometer timestamp */ |
||||
unsigned accelerometer2_errcount; /**< Error counter for accel 2 */ |
||||
float accelerometer2_temp; /**< Temperature of accel 2 */ |
||||
|
||||
int16_t magnetometer2_raw[3]; /**< Raw magnetic field in NED body frame */ |
||||
float magnetometer2_ga[3]; /**< Magnetic field in NED body frame, in Gauss */ |
||||
uint64_t magnetometer2_timestamp; /**< Magnetometer timestamp */ |
||||
unsigned magnetometer2_errcount; /**< Error counter for mag 2 */ |
||||
float magnetometer2_temp; /**< Temperature of mag 2 */ |
||||
|
||||
float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */ |
||||
float baro_alt_meter; /**< Altitude, already temp. comp. */ |
||||
float baro_temp_celcius; /**< Temperature in degrees celsius */ |
||||
uint64_t baro_timestamp; /**< Barometer timestamp */ |
||||
|
||||
float baro1_pres_mbar; /**< Barometric pressure, already temp. comp. */ |
||||
float baro1_alt_meter; /**< Altitude, already temp. comp. */ |
||||
float baro1_temp_celcius; /**< Temperature in degrees celsius */ |
||||
uint64_t baro1_timestamp; /**< Barometer timestamp */ |
||||
|
||||
float adc_voltage_v[10]; /**< ADC voltages of ADC Chan 10/11/12/13 or -1 */ |
||||
unsigned adc_mapping[10]; /**< Channel indices of each of these values */ |
||||
float mcu_temp_celcius; /**< Internal temperature measurement of MCU */ |
||||
|
||||
float differential_pressure_pa; /**< Airspeed sensor differential pressure */ |
||||
uint64_t differential_pressure_timestamp; /**< Last measurement timestamp */ |
||||
float differential_pressure_filtered_pa; /**< Low pass filtered airspeed sensor differential pressure reading */ |
||||
|
||||
float differential_pressure1_pa; /**< Airspeed sensor differential pressure */ |
||||
uint64_t differential_pressure1_timestamp; /**< Last measurement timestamp */ |
||||
float differential_pressure1_filtered_pa; /**< Low pass filtered airspeed sensor differential pressure reading */ |
||||
|
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(sensor_combined); |
||||
|
||||
#endif |
@ -1,87 +0,0 @@
@@ -1,87 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2012-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 vehicle_global_position.h |
||||
* Definition of the global fused WGS84 position uORB topic. |
||||
* |
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch> |
||||
* @author Julian Oes <julian@oes.ch> |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
*/ |
||||
|
||||
#ifndef VEHICLE_GLOBAL_POSITION_T_H_ |
||||
#define VEHICLE_GLOBAL_POSITION_T_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include <platforms/px4_defines.h> |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* Fused global position in WGS84. |
||||
* |
||||
* This struct contains global position estimation. It is not the raw GPS |
||||
* measurement (@see vehicle_gps_position). This topic is usually published by the position |
||||
* estimator, which will take more sources of information into account than just GPS, |
||||
* e.g. control inputs of the vehicle in a Kalman-filter implementation. |
||||
*/ |
||||
struct vehicle_global_position_s { |
||||
uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */ |
||||
uint64_t time_utc_usec; /**< GPS UTC timestamp in microseconds */ |
||||
double lat; /**< Latitude in degrees */ |
||||
double lon; /**< Longitude in degrees */ |
||||
float alt; /**< Altitude AMSL in meters */ |
||||
float vel_n; /**< Ground north velocity, m/s */ |
||||
float vel_e; /**< Ground east velocity, m/s */ |
||||
float vel_d; /**< Ground downside velocity, m/s */ |
||||
float yaw; /**< Yaw in radians -PI..+PI. */ |
||||
float eph; /**< Standard deviation of position estimate horizontally */ |
||||
float epv; /**< Standard deviation of position vertically */ |
||||
float terrain_alt; /**< Terrain altitude in m, WGS84 */ |
||||
bool terrain_alt_valid; /**< Terrain altitude estimate is valid */ |
||||
bool dead_reckoning; /**< True if this position is estimated through dead-reckoning*/ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vehicle_global_position); |
||||
|
||||
#endif |
@ -1,94 +0,0 @@
@@ -1,94 +0,0 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* Author: @author Thomas Gubler <thomasgubler@student.ethz.ch> |
||||
* @author Julian Oes <joes@student.ethz.ch> |
||||
* @author Lorenz Meier <lm@inf.ethz.ch> |
||||
* |
||||
* 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 vehicle_gps_position.h |
||||
* Definition of the GPS WGS84 uORB topic. |
||||
*/ |
||||
|
||||
#ifndef TOPIC_VEHICLE_GPS_H_ |
||||
#define TOPIC_VEHICLE_GPS_H_ |
||||
|
||||
#include <stdint.h> |
||||
#include "../uORB.h" |
||||
|
||||
/**
|
||||
* @addtogroup topics |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* GPS position in WGS84 coordinates. |
||||
*/ |
||||
struct vehicle_gps_position_s { |
||||
uint64_t timestamp_position; /**< Timestamp for position information */ |
||||
int32_t lat; /**< Latitude in 1E-7 degrees */ |
||||
int32_t lon; /**< Longitude in 1E-7 degrees */ |
||||
int32_t alt; /**< Altitude in 1E-3 meters (millimeters) above MSL */ |
||||
|
||||
uint64_t timestamp_variance; |
||||
float s_variance_m_s; /**< speed accuracy estimate m/s */ |
||||
float c_variance_rad; /**< course accuracy estimate rad */ |
||||
uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ |
||||
|
||||
float eph; /**< GPS HDOP horizontal dilution of position in m */ |
||||
float epv; /**< GPS VDOP horizontal dilution of position in m */ |
||||
|
||||
unsigned noise_per_ms; /**< */ |
||||
unsigned jamming_indicator; /**< */ |
||||
|
||||
uint64_t timestamp_velocity; /**< Timestamp for velocity informations */ |
||||
float vel_m_s; /**< GPS ground speed (m/s) */ |
||||
float vel_n_m_s; /**< GPS ground speed in m/s */ |
||||
float vel_e_m_s; /**< GPS ground speed in m/s */ |
||||
float vel_d_m_s; /**< GPS ground speed in m/s */ |
||||
float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */ |
||||
bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */ |
||||
|
||||
uint64_t timestamp_time; /**< Timestamp for time information */ |
||||
uint64_t time_utc_usec; /**< Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 */ |
||||
|
||||
uint8_t satellites_used; /**< Number of satellites used */ |
||||
}; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* register this as object request broker structure */ |
||||
ORB_DECLARE(vehicle_gps_position); |
||||
|
||||
#endif |
Loading…
Reference in new issue