Showing with 52 additions and 52 deletions.
  1. +1 −1 CONTRIBUTING.md
  2. +1 −1 Documentation/Doxyfile
  3. +1 −1 Documentation/px4_hil/UserGuide.md
  4. +3 −3 Tools/mavlink_px4.py
  5. +1 −1 msg/input_rc.msg
  6. +1 −1 msg/manual_control_setpoint.msg
  7. +1 −1 msg/rc_parameter_map.msg
  8. +1 −1 src/drivers/camera_trigger/camera_trigger.cpp
  9. +2 −2 src/drivers/gimbal/gimbal_params.c
  10. +1 −1 src/drivers/gps/mtk.h
  11. +2 −2 src/drivers/gps/ubx.cpp
  12. +1 −1 src/drivers/hott/hott_sensors/hott_sensors.cpp
  13. +1 −1 src/drivers/hott/messages.cpp
  14. +1 −1 src/drivers/hott/messages.h
  15. +1 −1 src/drivers/ms5611/ms5611_i2c.cpp
  16. +1 −1 src/drivers/pwm_input/pwm_input.cpp
  17. +2 −2 src/drivers/stm32/drv_hrt.c
  18. +1 −1 src/lib/launchdetection/LaunchMethod.h
  19. +2 −2 src/lib/launchdetection/launchdetection_params.c
  20. +1 −1 src/lib/rc/sbus.c
  21. +1 −1 src/modules/attitude_estimator_ekf/AttitudeEKF.m
  22. +1 −1 src/modules/attitude_estimator_ekf/codegen/AttitudeEKF.c
  23. +2 −2 src/modules/commander/commander_tests/state_machine_helper_test.cpp
  24. +1 −1 src/modules/local_position_estimator/BlockLocalPositionEstimator.hpp
  25. +2 −2 src/modules/mavlink/mavlink_main.cpp
  26. +1 −1 src/modules/muorb/adsp/uORBFastRpcChannel.cpp
  27. +1 −1 src/modules/muorb/krait/uORBKraitFastRpcChannel.cpp
  28. +3 −3 src/modules/sensors/sensors.cpp
  29. +1 −1 src/modules/systemlib/mixer/mixer.h
  30. +1 −1 src/modules/systemlib/up_cxxinitialize.c
  31. +1 −1 src/modules/systemlib/uthash/doc/userguide.txt
  32. +2 −2 src/platforms/posix/main.cpp
  33. +1 −1 src/platforms/posix/work_queue/dq_rem.c
  34. +3 −3 src/platforms/px4_nodehandle.h
  35. +1 −1 src/platforms/px4_posix.h
  36. +1 −1 src/platforms/px4_spi.h
  37. +1 −1 src/platforms/ros/nodes/commander/commander.h
  38. +1 −1 src/systemcmds/tests/test_eigen.cpp
  39. +1 −1 src/systemcmds/tests/test_mathlib.cpp
@@ -16,7 +16,7 @@ git checkout -b mydescriptivebranchname

### Edit and build the code

The [developer guide](http://px4.io/dev/start) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](http://px4.io/dev/code_style) when editing files.
The [developer guide](http://dev.px4.io/) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](http://px4.io/dev/code_style) when editing files.

### Commit your changes

@@ -281,7 +281,7 @@ TYPEDEF_HIDES_STRUCT = NO
# causing a significant performance penality.
# If the system has enough physical memory increasing the cache will improve the
# performance by keeping more symbols in memory. Note that the value works on
# a logarithmic scale so increasing the size by one will rougly double the
# a logarithmic scale so increasing the size by one will roughly double the
# memory usage. The cache size is given by this formula:
# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0,
# corresponding to a cache size of 2^16 = 65536 symbols
@@ -48,7 +48,7 @@ Download QGC from http://qgroundcontrol.org/downloads and install using the wind

## PX4

### Platfrom Requirements
### Platform Requirements
Linux or Eagle with a working IP interface (?? does this need further instructions?)

### Build Host Requirements
@@ -752,7 +752,7 @@ class MAVLink_gps_raw_int_message(MAVLink_message):
'''
The global position, as returned by the Global Positioning
System (GPS). This is NOT the global position
estimate of the sytem, but rather a RAW sensor value. See
estimate of the system, but rather a RAW sensor value. See
message GLOBAL_POSITION for the global position estimate.
Coordinate frame is right-handed, Z-axis up (GPS frame).
'''
@@ -2812,7 +2812,7 @@ def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel,
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position
estimate of the sytem, but rather a RAW sensor value.
estimate of the system, but rather a RAW sensor value.
See message GLOBAL_POSITION for the global position
estimate. Coordinate frame is right-handed, Z-axis up
(GPS frame).
@@ -2837,7 +2837,7 @@ def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, co
'''
The global position, as returned by the Global Positioning System
(GPS). This is NOT the global position
estimate of the sytem, but rather a RAW sensor value.
estimate of the system, but rather a RAW sensor value.
See message GLOBAL_POSITION for the global position
estimate. Coordinate frame is right-handed, Z-axis up
(GPS frame).
@@ -14,7 +14,7 @@ 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.
bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usUally 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
@@ -26,7 +26,7 @@ float32 z # throttle stick position 0..1
# in general the value corresponds to the demanded throttle by the user,
# if the input is used for setting the setpoint of a vertical position
# controller any value > 0.5 means up and any value < 0.5 means down
float32 r # yaw stick/twist positon, -1..1
float32 r # yaw stick/twist position, -1..1
# in general corresponds to the righthand rotation around the vertical
# (downwards) axis of the vehicle
float32 flaps # flap position
@@ -6,6 +6,6 @@ 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] value0 # initial value around which the parameter value is changed
float32[3] value_min # minimal parameter value
float32[3] value_max # minimal parameter value
@@ -34,7 +34,7 @@
/**
* @file camera_trigger.cpp
*
* External camera-IMU synchronisation and triggering via FMU auxillary pins.
* External camera-IMU synchronisation and triggering via FMU auxiliary pins.
*
* @author Mohammed Kabir <mhkabir98@gmail.com>
*/
@@ -55,11 +55,11 @@
PARAM_DEFINE_INT32(GMB_USE_MNT, 0);

/**
* Auxilary switch to set mount operation mode.
* Auxiliary switch to set mount operation mode.
*
* Set to 0 to disable manual mode control.
*
* If set to an auxilary switch:
* If set to an auxiliary switch:
* Switch off means the gimbal is put into safe/locked position.
* Switch on means the gimbal can move freely, and landing gear
* will be retracted if applicable.
@@ -72,7 +72,7 @@ typedef struct {
uint32_t msl_altitude; ///< MSL altitude in meters * 10^2
uint32_t ground_speed; ///< velocity in m/s
int32_t heading; ///< heading in degrees * 10^2
uint8_t satellites; ///< number of sattelites used
uint8_t satellites; ///< number of satellites used
uint8_t fix_type; ///< fix type: XXX correct for that
uint32_t date;
uint32_t utc_time;
@@ -44,8 +44,8 @@
* @author Hannes Delago
* (rework, add ubx7+ compatibility)
*
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-bloxM8_ReceiverDescriptionProtocolSpec_%28UBX-13003221%29_Public.pdf
* @see https://www2.u-blox.com/images/downloads/Product_Docs/u-blox6-GPS-GLONASS-QZSS-V14_ReceiverDescriptionProtocolSpec_Public_(GPS.G6-SW-12013).pdf
* @see https://www.u-blox.com/sites/default/files/products/documents/u-bloxM8_ReceiverDescrProtSpec_%28UBX-13003221%29_Public.pdf
*/

#include <assert.h>
@@ -182,7 +182,7 @@ hott_sensors_thread_main(int argc, char *argv[])

recv_data(uart, &buffer[0], &size, &id);

// Determine which moduel sent it and process accordingly.
// Determine which module sent it and process accordingly.
if (id == GAM_SENSOR_ID) {
publish_gam_message(buffer);

@@ -291,7 +291,7 @@ build_gps_response(uint8_t *buffer, size_t *size)
msg.altitude_L = (uint8_t)alt & 0xff;
msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;

/* Get any (and probably only ever one) _home_sub postion report */
/* Get any (and probably only ever one) _home_sub position report */
bool updated;
orb_check(_home_sub, &updated);

@@ -211,7 +211,7 @@ struct gps_module_msg {
uint8_t resolution_L; /**< 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */
uint8_t resolution_H; /**< 117 = High Byte m/s resolution 0.01m */
uint8_t unknown1; /**< 120 = 0m/3s */
uint8_t gps_num_sat; /**< GPS.Satellites (number of satelites) (1 byte) */
uint8_t gps_num_sat; /**< GPS.Satellites (number of satellites) (1 byte) */
uint8_t gps_fix_char; /**< GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */
uint8_t home_direction; /**< HomeDirection (direction from starting point to Model position) (1 byte) */
uint8_t angle_x_direction; /**< angle x-direction (1 byte) */
@@ -265,7 +265,7 @@ MS5611_I2C::_read_prom()

/* check if all bytes are zero */
if (i == 0) {
/* initalize to first byte read */
/* initialize to first byte read */
last_val = prom_buf[0];
}

@@ -536,7 +536,7 @@ void PWMIN::print_info(void)


/*
* Handle the interupt, gathering pulse data
* Handle the interrupt, gathering pulse data
*/
static int pwmin_tim_isr(int irq, void *context)
{
@@ -599,7 +599,7 @@ hrt_ppm_decode(uint32_t status)
#endif /* HRT_PPM_CHANNEL */

/**
* Handle the compare interupt by calling the callout dispatcher
* Handle the compare interrupt by calling the callout dispatcher
* and then re-scheduling the next deadline.
*/
static int
@@ -750,7 +750,7 @@ hrt_store_absolute_time(volatile hrt_abstime *now)
}

/**
* Initalise the high-resolution timing module.
* Initialise the high-resolution timing module.
*/
void
hrt_init(void)
@@ -51,7 +51,7 @@ enum LaunchDetectionResult {
up and still be set to 'throttlePreTakeoff'.
For instance this is used to have a delay for the motor
when launching a fixed wing aircraft from a bungee */
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, teh controller should control
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, the controller should control
attitude and also throttle up the motors. */
};

@@ -54,7 +54,7 @@
PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);

/**
* Catapult accelerometer theshold.
* Catapult accelerometer threshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*
@@ -64,7 +64,7 @@ PARAM_DEFINE_INT32(LAUN_ALL_ON, 0);
PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);

/**
* Catapult time theshold.
* Catapult time threshold.
*
* LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
*
@@ -615,7 +615,7 @@ sbus_decode(uint64_t frame_time, uint8_t *frame, uint16_t *values, uint16_t *num
*
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
* condition as fail-safe greatly reduces the reliability and range of the radio link,
* e.g. by prematurely issueing return-to-launch!!! */
* e.g. by prematurely issuing return-to-launch!!! */

*sbus_failsafe = false;
*sbus_frame_drop = true;
@@ -2,7 +2,7 @@
= AttitudeEKF(approx_prediction,use_inertia_matrix,zFlag,dt,z,q_rotSpeed,q_rotAcc,q_acc,q_mag,r_gyro,r_accel,r_mag,J)


%LQG Postion Estimator and Controller
%LQG Position Estimator and Controller
% Observer:
% x[n|n] = x[n|n-1] + M(y[n] - Cx[n|n-1] - Du[n])
% x[n+1|n] = Ax[n|n] + Bu[n]
@@ -499,7 +499,7 @@ void AttitudeEKF(unsigned char approx_prediction, unsigned char

float b_z[6];

/* LQG Postion Estimator and Controller */
/* LQG Position Estimator and Controller */
/* Observer: */
/* x[n|n] = x[n|n-1] + M(y[n] - Cx[n|n-1] - Du[n]) */
/* x[n+1|n] = Ax[n|n] + Bu[n] */
@@ -75,11 +75,11 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
} ArmingTransitionVolatileState_t;

// This structure represents a test case for arming_state_transition. It contains the machine
// state prior to transtion, the requested state to transition to and finally the expected
// state prior to transition, the requested state to transition to and finally the expected
// machine state after transition.
typedef struct {
const char* assertMsg; // Text to show when test case fails
ArmingTransitionVolatileState_t current_state; // Machine state prior to transtion
ArmingTransitionVolatileState_t current_state; // Machine state prior to transition
hil_state_t hil_state; // Current vehicle_status_s.hil_state
bool condition_system_sensors_initialized; // Current vehicle_status_s.condition_system_sensors_initialized
bool safety_switch_available; // Current safety_s.safety_switch_available
@@ -145,7 +145,7 @@ class BlockLocalPositionEstimator : public control::SuperBlock
// predict the next state
void predict();

// correct the state prediction wtih a measurement
// correct the state prediction with a measurement
void correctBaro();
void correctGps();
void correctLidar();
@@ -844,7 +844,7 @@ Mavlink::get_free_tx_buf()
*/
int buf_free = 0;

// if we are using network sockets, return max lenght of one packet
// if we are using network sockets, return max length of one packet
if (get_protocol() == UDP || get_protocol() == TCP ) {
return 1500;
} else {
@@ -1046,7 +1046,7 @@ Mavlink::init_udp()
return;
}

/* set default target address, but not for onboard mode (will be set on first recieved packet) */
/* set default target address, but not for onboard mode (will be set on first received packet) */
memset((char *)&_src_addr, 0, sizeof(_src_addr));
if (_mode != MAVLINK_MODE_ONBOARD) {
set_client_source_initialized();
@@ -35,7 +35,7 @@
#include <algorithm>
#include <drivers/drv_hrt.h>

// static intialization.
// static initialization.
uORB::FastRpcChannel uORB::FastRpcChannel::_Instance;

static unsigned long _dropped_pkts;
@@ -44,7 +44,7 @@ uORB::KraitFastRpcChannel uORB::KraitFastRpcChannel::_Instance;

static void DumpData(uint8_t *buffer, int32_t length, int32_t num_topics);

// static intialization.
// static initialization.
static std::string _log_file_name = "./hex_dump.txt";

static unsigned long _snd_msg_min = 0xFFFFFF;
@@ -185,7 +185,7 @@ class Sensors
switch_pos_t get_rc_sw2pos_position(uint8_t func, float on_th, bool on_inv);

/**
* Update paramters from RC channels if the functionality is activated and the
* Update parameters from RC channels if the functionality is activated and the
* input has changed since the last update
*
* @param
@@ -346,7 +346,7 @@ class Sensors
param_t rc_map_aux5;

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
param_t rc_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< param handles for the parameters which are bound
to a RC channel, equivalent float values in the
_parameters struct are not existing
because these parameters are never read. */
@@ -1568,7 +1568,7 @@ Sensors::rc_parameter_map_poll(bool forced)
if (map_updated) {
orb_copy(ORB_ID(rc_parameter_map), _rc_parameter_map_sub, &_rc_parameter_map);

/* update paramter handles to which the RC channels are mapped */
/* update parameter handles to which the RC channels are mapped */
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)
@@ -481,7 +481,7 @@ enum class MultirotorGeometry : MultirotorGeometryUnderlyingType;
* compared to thrust.
* @param yaw_wcale Scaling factor applied to yaw inputs compared
* to thrust.
* @param idle_speed Minumum rotor control output value; usually
* @param idle_speed Minimum rotor control output value; usually
* tuned to ensure that rotors never stall at the
* low end of their control range.
*/
@@ -118,7 +118,7 @@ extern uint32_t _etext;
* This function should then be called in the application-specific
* user_start logic in order to perform the C++ initialization. NOTE
* that no component of the core NuttX RTOS logic is involved; This
* function defintion only provides the 'contract' between application
* function definition only provides the 'contract' between application
* specific C++ code and platform-specific toolchain support
*
***************************************************************************/
@@ -1058,7 +1058,7 @@ always used with the `users_by_name` hash table).

Several sort orders
~~~~~~~~~~~~~~~~~~~
It comes as no suprise that two hash tables can have different sort orders, but
It comes as no surprise that two hash tables can have different sort orders, but
this fact can also be used advantageously to sort the 'same items' in several
ways. This is based on the ability to store a structure in several hash tables.

@@ -35,7 +35,7 @@
* Basic shell to execute builtin "apps"
*
* @author Mark Charlebois <charlebm@gmail.com>
* @auther Roman Bapst <bapstroman@gmail.com>
* @author Roman Bapst <bapstroman@gmail.com>
*/

#include <iostream>
@@ -238,7 +238,7 @@ int main(int argc, char **argv)
const char *folderpath = "/rootfs/";

if (nullptr == getcwd(pwd_path, sizeof(pwd_path))) {
PX4_ERR("Failed aquiring working dir, abort.");
PX4_ERR("Failed acquiring working dir, abort.");
exit(1);
}

@@ -51,7 +51,7 @@
/************************************************************
* Name: dq_rem
*
* Descripton:
* Description:
* dq_rem removes 'node' from 'queue'
*
************************************************************/