aboutsummaryrefslogtreecommitdiff
path: root/src/modules/systemlib
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-11-08 21:56:11 +0400
committerAnton Babushkin <anton.babushkin@me.com>2013-11-08 21:56:11 +0400
commite8224376ca4d32e948cbee75bfecf8a30f3e98ea (patch)
tree65290003878c65247d99ad21849a6f3cbeac2e35 /src/modules/systemlib
parent28bf8e238e35a7bbba81f86e63cd0a49226673a4 (diff)
parentc63995e91c188b476aa2608b42a366f68dced423 (diff)
downloadpx4-firmware-e8224376ca4d32e948cbee75bfecf8a30f3e98ea.tar.gz
px4-firmware-e8224376ca4d32e948cbee75bfecf8a30f3e98ea.tar.bz2
px4-firmware-e8224376ca4d32e948cbee75bfecf8a30f3e98ea.zip
Merge branch 'master' into vector_control
Diffstat (limited to 'src/modules/systemlib')
-rw-r--r--src/modules/systemlib/airspeed.c16
-rw-r--r--src/modules/systemlib/airspeed.h8
-rw-r--r--src/modules/systemlib/conversions.c97
-rw-r--r--src/modules/systemlib/conversions.h29
-rw-r--r--src/modules/systemlib/geo/geo.c438
-rw-r--r--src/modules/systemlib/geo/geo.h129
-rw-r--r--src/modules/systemlib/mavlink_log.c128
-rw-r--r--src/modules/systemlib/mixer/mixer.cpp45
-rw-r--r--src/modules/systemlib/mixer/mixer.h26
-rw-r--r--src/modules/systemlib/mixer/mixer_group.cpp15
-rw-r--r--src/modules/systemlib/mixer/mixer_load.c100
-rw-r--r--src/modules/systemlib/mixer/mixer_load.h51
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp46
-rw-r--r--src/modules/systemlib/mixer/mixer_simple.cpp68
-rw-r--r--src/modules/systemlib/mixer/module.mk3
-rwxr-xr-xsrc/modules/systemlib/mixer/multi_tables13
-rw-r--r--src/modules/systemlib/module.mk5
-rw-r--r--src/modules/systemlib/param/param.c71
-rw-r--r--src/modules/systemlib/perf_counter.c26
-rw-r--r--src/modules/systemlib/perf_counter.h8
-rw-r--r--src/modules/systemlib/pid/pid.c38
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c133
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.h77
-rw-r--r--src/modules/systemlib/rc_check.c151
-rw-r--r--src/modules/systemlib/rc_check.h52
-rw-r--r--src/modules/systemlib/systemlib.c18
-rw-r--r--src/modules/systemlib/systemlib.h6
27 files changed, 1023 insertions, 774 deletions
diff --git a/src/modules/systemlib/airspeed.c b/src/modules/systemlib/airspeed.c
index e01cc4dda..310fbf60f 100644
--- a/src/modules/systemlib/airspeed.c
+++ b/src/modules/systemlib/airspeed.c
@@ -42,7 +42,7 @@
#include <stdio.h>
#include <math.h>
-#include "conversions.h"
+#include <geo/geo.h>
#include "airspeed.h"
@@ -95,17 +95,21 @@ float calc_true_airspeed_from_indicated(float speed_indicated, float pressure_am
float calc_true_airspeed(float total_pressure, float static_pressure, float temperature_celsius)
{
float density = get_air_density(static_pressure, temperature_celsius);
+
if (density < 0.0001f || !isfinite(density)) {
- density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C;
-// printf("[airspeed] Invalid air density, using density at sea level\n");
+ density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C;
}
float pressure_difference = total_pressure - static_pressure;
- if(pressure_difference > 0) {
+ if (pressure_difference > 0) {
return sqrtf((2.0f*(pressure_difference)) / density);
- } else
- {
+ } else {
return -sqrtf((2.0f*fabsf(pressure_difference)) / density);
}
}
+
+float get_air_density(float static_pressure, float temperature_celsius)
+{
+ return static_pressure / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS));
+}
diff --git a/src/modules/systemlib/airspeed.h b/src/modules/systemlib/airspeed.h
index def53f0c1..8dccaab9c 100644
--- a/src/modules/systemlib/airspeed.h
+++ b/src/modules/systemlib/airspeed.h
@@ -85,6 +85,14 @@
*/
__EXPORT float calc_true_airspeed(float total_pressure, float static_pressure, float temperature_celsius);
+ /**
+ * Calculates air density.
+ *
+ * @param static_pressure ambient pressure in millibar
+ * @param temperature_celcius air / ambient temperature in celcius
+ */
+__EXPORT float get_air_density(float static_pressure, float temperature_celsius);
+
__END_DECLS
#endif
diff --git a/src/modules/systemlib/conversions.c b/src/modules/systemlib/conversions.c
index ac94252c5..9105d83cb 100644
--- a/src/modules/systemlib/conversions.c
+++ b/src/modules/systemlib/conversions.c
@@ -55,100 +55,3 @@ int16_t_from_bytes(uint8_t bytes[])
return u.w;
}
-
-void rot2quat(const float R[9], float Q[4])
-{
- float q0_2;
- float q1_2;
- float q2_2;
- float q3_2;
- int32_t idx;
-
- /* conversion of rotation matrix to quaternion
- * choose the largest component to begin with */
- q0_2 = (((1.0F + R[0]) + R[4]) + R[8]) / 4.0F;
- q1_2 = (((1.0F + R[0]) - R[4]) - R[8]) / 4.0F;
- q2_2 = (((1.0F - R[0]) + R[4]) - R[8]) / 4.0F;
- q3_2 = (((1.0F - R[0]) - R[4]) + R[8]) / 4.0F;
-
- idx = 0;
-
- if (q0_2 < q1_2) {
- q0_2 = q1_2;
-
- idx = 1;
- }
-
- if (q0_2 < q2_2) {
- q0_2 = q2_2;
- idx = 2;
- }
-
- if (q0_2 < q3_2) {
- q0_2 = q3_2;
- idx = 3;
- }
-
- q0_2 = sqrtf(q0_2);
-
- /* solve for the remaining three components */
- if (idx == 0) {
- q1_2 = q0_2;
- q2_2 = (R[5] - R[7]) / 4.0F / q0_2;
- q3_2 = (R[6] - R[2]) / 4.0F / q0_2;
- q0_2 = (R[1] - R[3]) / 4.0F / q0_2;
-
- } else if (idx == 1) {
- q2_2 = q0_2;
- q1_2 = (R[5] - R[7]) / 4.0F / q0_2;
- q3_2 = (R[3] + R[1]) / 4.0F / q0_2;
- q0_2 = (R[6] + R[2]) / 4.0F / q0_2;
-
- } else if (idx == 2) {
- q3_2 = q0_2;
- q1_2 = (R[6] - R[2]) / 4.0F / q0_2;
- q2_2 = (R[3] + R[1]) / 4.0F / q0_2;
- q0_2 = (R[7] + R[5]) / 4.0F / q0_2;
-
- } else {
- q1_2 = (R[1] - R[3]) / 4.0F / q0_2;
- q2_2 = (R[6] + R[2]) / 4.0F / q0_2;
- q3_2 = (R[7] + R[5]) / 4.0F / q0_2;
- }
-
- /* return values */
- Q[0] = q1_2;
- Q[1] = q2_2;
- Q[2] = q3_2;
- Q[3] = q0_2;
-}
-
-void quat2rot(const float Q[4], float R[9])
-{
- float q0_2;
- float q1_2;
- float q2_2;
- float q3_2;
-
- memset(&R[0], 0, 9U * sizeof(float));
-
- q0_2 = Q[0] * Q[0];
- q1_2 = Q[1] * Q[1];
- q2_2 = Q[2] * Q[2];
- q3_2 = Q[3] * Q[3];
-
- R[0] = ((q0_2 + q1_2) - q2_2) - q3_2;
- R[3] = 2.0F * (Q[1] * Q[2] - Q[0] * Q[3]);
- R[6] = 2.0F * (Q[1] * Q[3] + Q[0] * Q[2]);
- R[1] = 2.0F * (Q[1] * Q[2] + Q[0] * Q[3]);
- R[4] = ((q0_2 + q2_2) - q1_2) - q3_2;
- R[7] = 2.0F * (Q[2] * Q[3] - Q[0] * Q[1]);
- R[2] = 2.0F * (Q[1] * Q[3] - Q[0] * Q[2]);
- R[5] = 2.0F * (Q[2] * Q[3] + Q[0] * Q[1]);
- R[8] = ((q0_2 + q3_2) - q1_2) - q2_2;
-}
-
-float get_air_density(float static_pressure, float temperature_celsius)
-{
- return static_pressure / (CONSTANTS_AIR_GAS_CONST * (temperature_celsius - CONSTANTS_ABSOLUTE_NULL_CELSIUS));
-}
diff --git a/src/modules/systemlib/conversions.h b/src/modules/systemlib/conversions.h
index 064426f21..dc383e770 100644
--- a/src/modules/systemlib/conversions.h
+++ b/src/modules/systemlib/conversions.h
@@ -43,7 +43,6 @@
#define CONVERSIONS_H_
#include <float.h>
#include <stdint.h>
-#include <systemlib/geo/geo.h>
__BEGIN_DECLS
@@ -57,34 +56,6 @@ __BEGIN_DECLS
*/
__EXPORT int16_t int16_t_from_bytes(uint8_t bytes[]);
-/**
- * Converts a 3 x 3 rotation matrix to an unit quaternion.
- *
- * All orientations are expressed in NED frame.
- *
- * @param R rotation matrix to convert
- * @param Q quaternion to write back to
- */
-__EXPORT void rot2quat(const float R[9], float Q[4]);
-
-/**
- * Converts an unit quaternion to a 3 x 3 rotation matrix.
- *
- * All orientations are expressed in NED frame.
- *
- * @param Q quaternion to convert
- * @param R rotation matrix to write back to
- */
-__EXPORT void quat2rot(const float Q[4], float R[9]);
-
-/**
- * Calculates air density.
- *
- * @param static_pressure ambient pressure in millibar
- * @param temperature_celcius air / ambient temperature in celcius
- */
-__EXPORT float get_air_density(float static_pressure, float temperature_celsius);
-
__END_DECLS
#endif /* CONVERSIONS_H_ */
diff --git a/src/modules/systemlib/geo/geo.c b/src/modules/systemlib/geo/geo.c
deleted file mode 100644
index 6463e6489..000000000
--- a/src/modules/systemlib/geo/geo.c
+++ /dev/null
@@ -1,438 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.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 geo.c
- *
- * Geo / math functions to perform geodesic calculations
- *
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- */
-
-#include <systemlib/geo/geo.h>
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <pthread.h>
-#include <stdio.h>
-#include <math.h>
-#include <stdbool.h>
-
-
-/* values for map projection */
-static double phi_1;
-static double sin_phi_1;
-static double cos_phi_1;
-static double lambda_0;
-static double scale;
-
-__EXPORT void map_projection_init(double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
-{
- /* notation and formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- phi_1 = lat_0 / 180.0 * M_PI;
- lambda_0 = lon_0 / 180.0 * M_PI;
-
- sin_phi_1 = sin(phi_1);
- cos_phi_1 = cos(phi_1);
-
- /* calculate local scale by using the relation of true distance and the distance on plane */ //TODO: this is a quick solution, there are probably easier ways to determine the scale
-
- /* 1) calculate true distance d on sphere to a point: http://www.movable-type.co.uk/scripts/latlong.html */
- const double r_earth = 6371000;
-
- double lat1 = phi_1;
- double lon1 = lambda_0;
-
- double lat2 = phi_1 + 0.5 / 180 * M_PI;
- double lon2 = lambda_0 + 0.5 / 180 * M_PI;
- double sin_lat_2 = sin(lat2);
- double cos_lat_2 = cos(lat2);
- double d = acos(sin(lat1) * sin_lat_2 + cos(lat1) * cos_lat_2 * cos(lon2 - lon1)) * r_earth;
-
- /* 2) calculate distance rho on plane */
- double k_bar = 0;
- double c = acos(sin_phi_1 * sin_lat_2 + cos_phi_1 * cos_lat_2 * cos(lon2 - lambda_0));
-
- if (0 != c)
- k_bar = c / sin(c);
-
- double x2 = k_bar * (cos_lat_2 * sin(lon2 - lambda_0)); //Projection of point 2 on plane
- double y2 = k_bar * ((cos_phi_1 * sin_lat_2 - sin_phi_1 * cos_lat_2 * cos(lon2 - lambda_0)));
- double rho = sqrt(pow(x2, 2) + pow(y2, 2));
-
- scale = d / rho;
-
-}
-
-__EXPORT void map_projection_project(double lat, double lon, float *x, float *y)
-{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- double phi = lat / 180.0 * M_PI;
- double lambda = lon / 180.0 * M_PI;
-
- double sin_phi = sin(phi);
- double cos_phi = cos(phi);
-
- double k_bar = 0;
- /* using small angle approximation (formula in comment is without aproximation) */
- double c = acos(sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2)); //double c = acos( sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * cos(lambda - lambda_0) );
-
- if (0 != c)
- k_bar = c / sin(c);
-
- /* using small angle approximation (formula in comment is without aproximation) */
- *y = k_bar * (cos_phi * (lambda - lambda_0)) * scale;//*y = k_bar * (cos_phi * sin(lambda - lambda_0)) * scale;
- *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2))) * scale; // *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * cos(lambda - lambda_0))) * scale;
-
-// printf("%phi_1=%.10f, lambda_0 =%.10f\n", phi_1, lambda_0);
-}
-
-__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon)
-{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
-
- double x_descaled = x / scale;
- double y_descaled = y / scale;
-
- double c = sqrt(pow(x_descaled, 2) + pow(y_descaled, 2));
- double sin_c = sin(c);
- double cos_c = cos(c);
-
- double lat_sphere = 0;
-
- if (c != 0)
- lat_sphere = asin(cos_c * sin_phi_1 + (x_descaled * sin_c * cos_phi_1) / c);
- else
- lat_sphere = asin(cos_c * sin_phi_1);
-
-// printf("lat_sphere = %.10f\n",lat_sphere);
-
- double lon_sphere = 0;
-
- if (phi_1 == M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 - y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(-y_descaled, x_descaled));
-
- } else if (phi_1 == -M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 + y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(y_descaled, x_descaled));
-
- } else {
-
- lon_sphere = (lambda_0 + atan2(y_descaled * sin_c , c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c));
- //using small angle approximation
-// double denominator = (c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c);
-// if(denominator != 0)
-// {
-// lon_sphere = (lambda_0 + (y_descaled * sin_c) / denominator);
-// }
-// else
-// {
-// ...
-// }
- }
-
-// printf("lon_sphere = %.10f\n",lon_sphere);
-
- *lat = lat_sphere * 180.0 / M_PI;
- *lon = lon_sphere * 180.0 / M_PI;
-
-}
-
-
-__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
-{
- double lat_now_rad = lat_now / 180.0d * M_PI;
- double lon_now_rad = lon_now / 180.0d * M_PI;
- double lat_next_rad = lat_next / 180.0d * M_PI;
- double lon_next_rad = lon_next / 180.0d * M_PI;
-
-
- double d_lat = lat_next_rad - lat_now_rad;
- double d_lon = lon_next_rad - lon_now_rad;
-
- double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0d) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad);
- double c = 2.0d * atan2(sqrt(a), sqrt(1.0d - a));
-
- const double radius_earth = 6371000.0d;
- return radius_earth * c;
-}
-
-__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
-{
- double lat_now_rad = lat_now * M_DEG_TO_RAD;
- double lon_now_rad = lon_now * M_DEG_TO_RAD;
- double lat_next_rad = lat_next * M_DEG_TO_RAD;
- double lon_next_rad = lon_next * M_DEG_TO_RAD;
-
- double d_lat = lat_next_rad - lat_now_rad;
- double d_lon = lon_next_rad - lon_now_rad;
-
- /* conscious mix of double and float trig function to maximize speed and efficiency */
- float theta = atan2f(sin(d_lon) * cos(lat_next_rad) , cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(lat_next_rad) * cos(d_lon));
-
- theta = _wrap_pi(theta);
-
- return theta;
-}
-
-// Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu>
-
-__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end)
-{
-// This function returns the distance to the nearest point on the track line. Distance is positive if current
-// position is right of the track and negative if left of the track as seen from a point on the track line
-// headed towards the end point.
-
- float dist_to_end;
- float bearing_end;
- float bearing_track;
- float bearing_diff;
-
- int return_value = ERROR; // Set error flag, cleared when valid result calculated.
- crosstrack_error->past_end = false;
- crosstrack_error->distance = 0.0f;
- crosstrack_error->bearing = 0.0f;
-
- // Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_start == 0.0d || lon_start == 0.0d || lat_end == 0.0d || lon_end == 0.0d) return return_value;
-
- bearing_end = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
- bearing_track = get_bearing_to_next_waypoint(lat_start, lon_start, lat_end, lon_end);
- bearing_diff = bearing_track - bearing_end;
- bearing_diff = _wrap_pi(bearing_diff);
-
- // Return past_end = true if past end point of line
- if (bearing_diff > M_PI_2_F || bearing_diff < -M_PI_2_F) {
- crosstrack_error->past_end = true;
- return_value = OK;
- return return_value;
- }
-
- dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
- crosstrack_error->distance = (dist_to_end) * sin(bearing_diff);
-
- if (sin(bearing_diff) >= 0) {
- crosstrack_error->bearing = _wrap_pi(bearing_track - M_PI_2_F);
-
- } else {
- crosstrack_error->bearing = _wrap_pi(bearing_track + M_PI_2_F);
- }
-
- return_value = OK;
-
- return return_value;
-
-}
-
-
-__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
- float radius, float arc_start_bearing, float arc_sweep)
-{
- // This function returns the distance to the nearest point on the track arc. Distance is positive if current
- // position is right of the arc and negative if left of the arc as seen from the closest point on the arc and
- // headed towards the end point.
-
- // Determine if the current position is inside or outside the sector between the line from the center
- // to the arc start and the line from the center to the arc end
- float bearing_sector_start;
- float bearing_sector_end;
- float bearing_now = get_bearing_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
- bool in_sector;
-
- int return_value = ERROR; // Set error flag, cleared when valid result calculated.
- crosstrack_error->past_end = false;
- crosstrack_error->distance = 0.0f;
- crosstrack_error->bearing = 0.0f;
-
- // Return error if arguments are bad
- if (lat_now == 0.0d || lon_now == 0.0d || lat_center == 0.0d || lon_center == 0.0d || radius == 0.0d) return return_value;
-
-
- if (arc_sweep >= 0) {
- bearing_sector_start = arc_start_bearing;
- bearing_sector_end = arc_start_bearing + arc_sweep;
-
- if (bearing_sector_end > 2.0f * M_PI_F) bearing_sector_end -= M_TWOPI_F;
-
- } else {
- bearing_sector_end = arc_start_bearing;
- bearing_sector_start = arc_start_bearing - arc_sweep;
-
- if (bearing_sector_start < 0.0f) bearing_sector_start += M_TWOPI_F;
- }
-
- in_sector = false;
-
- // Case where sector does not span zero
- if (bearing_sector_end >= bearing_sector_start && bearing_now >= bearing_sector_start && bearing_now <= bearing_sector_end) in_sector = true;
-
- // Case where sector does span zero
- if (bearing_sector_end < bearing_sector_start && (bearing_now > bearing_sector_start || bearing_now < bearing_sector_end)) in_sector = true;
-
- // If in the sector then calculate distance and bearing to closest point
- if (in_sector) {
- crosstrack_error->past_end = false;
- float dist_to_center = get_distance_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
-
- if (dist_to_center <= radius) {
- crosstrack_error->distance = radius - dist_to_center;
- crosstrack_error->bearing = bearing_now + M_PI_F;
-
- } else {
- crosstrack_error->distance = dist_to_center - radius;
- crosstrack_error->bearing = bearing_now;
- }
-
- // If out of the sector then calculate dist and bearing to start or end point
-
- } else {
-
- // Use the approximation that 111,111 meters in the y direction is 1 degree (of latitude)
- // and 111,111 * cos(latitude) meters in the x direction is 1 degree (of longitude) to
- // calculate the position of the start and end points. We should not be doing this often
- // as this function generally will not be called repeatedly when we are out of the sector.
-
- // TO DO - this is messed up and won't compile
- float start_disp_x = radius * sin(arc_start_bearing);
- float start_disp_y = radius * cos(arc_start_bearing);
- float end_disp_x = radius * sin(_wrapPI(arc_start_bearing + arc_sweep));
- float end_disp_y = radius * cos(_wrapPI(arc_start_bearing + arc_sweep));
- float lon_start = lon_now + start_disp_x / 111111.0d;
- float lat_start = lat_now + start_disp_y * cos(lat_now) / 111111.0d;
- float lon_end = lon_now + end_disp_x / 111111.0d;
- float lat_end = lat_now + end_disp_y * cos(lat_now) / 111111.0d;
- float dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
- float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
-
-
- if (dist_to_start < dist_to_end) {
- crosstrack_error->distance = dist_to_start;
- crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
-
- } else {
- crosstrack_error->past_end = true;
- crosstrack_error->distance = dist_to_end;
- crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
- }
-
- }
-
- crosstrack_error->bearing = _wrapPI(crosstrack_error->bearing);
- return_value = OK;
- return return_value;
-}
-
-__EXPORT float _wrap_pi(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing) || bearing == 0) {
- return bearing;
- }
-
- int c = 0;
-
- while (bearing > M_PI_F && c < 30) {
- bearing -= M_TWOPI_F;
- c++;
- }
-
- c = 0;
-
- while (bearing <= -M_PI_F && c < 30) {
- bearing += M_TWOPI_F;
- c++;
- }
-
- return bearing;
-}
-
-__EXPORT float _wrap_2pi(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing)) {
- return bearing;
- }
-
- while (bearing >= M_TWOPI_F) {
- bearing = bearing - M_TWOPI_F;
- }
-
- while (bearing < 0.0f) {
- bearing = bearing + M_TWOPI_F;
- }
-
- return bearing;
-}
-
-__EXPORT float _wrap_180(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing)) {
- return bearing;
- }
-
- while (bearing > 180.0f) {
- bearing = bearing - 360.0f;
- }
-
- while (bearing <= -180.0f) {
- bearing = bearing + 360.0f;
- }
-
- return bearing;
-}
-
-__EXPORT float _wrap_360(float bearing)
-{
- /* value is inf or NaN */
- if (!isfinite(bearing)) {
- return bearing;
- }
-
- while (bearing >= 360.0f) {
- bearing = bearing - 360.0f;
- }
-
- while (bearing < 0.0f) {
- bearing = bearing + 360.0f;
- }
-
- return bearing;
-}
-
-
diff --git a/src/modules/systemlib/geo/geo.h b/src/modules/systemlib/geo/geo.h
deleted file mode 100644
index dadec51ec..000000000
--- a/src/modules/systemlib/geo/geo.h
+++ /dev/null
@@ -1,129 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.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 geo.h
- *
- * Definition of geo / math functions to perform geodesic calculations
- *
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu>
- */
-
-#pragma once
-
-__BEGIN_DECLS
-
-#include <stdbool.h>
-
-#define CONSTANTS_ONE_G 9.80665f /* m/s^2 */
-#define CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C 1.225f /* kg/m^3 */
-#define CONSTANTS_AIR_GAS_CONST 287.1f /* J/(kg * K) */
-#define CONSTANTS_ABSOLUTE_NULL_CELSIUS -273.15f /* °C */
-#define CONSTANTS_RADIUS_OF_EARTH 6371000 /* meters (m) */
-
-/* compatibility aliases */
-#define RADIUS_OF_EARTH CONSTANTS_RADIUS_OF_EARTH
-#define GRAVITY_MSS CONSTANTS_ONE_G
-
-// XXX remove
-struct crosstrack_error_s {
- bool past_end; // Flag indicating we are past the end of the line/arc segment
- float distance; // Distance in meters to closest point on line/arc
- float bearing; // Bearing in radians to closest point on line/arc
-} ;
-
-/**
- * Initializes the map transformation.
- *
- * Initializes the transformation between the geographic coordinate system and the azimuthal equidistant plane
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-__EXPORT void map_projection_init(double lat_0, double lon_0);
-
-/**
- * Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
- * @param x north
- * @param y east
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-__EXPORT void map_projection_project(double lat, double lon, float *x, float *y);
-
-/**
- * Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
- *
- * @param x north
- * @param y east
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon);
-
-/**
- * Returns the distance to the next waypoint in meters.
- *
- * @param lat_now current position in degrees (47.1234567°, not 471234567°)
- * @param lon_now current position in degrees (8.1234567°, not 81234567°)
- * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
- * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
- */
-__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
-
-/**
- * Returns the bearing to the next waypoint in radians.
- *
- * @param lat_now current position in degrees (47.1234567°, not 471234567°)
- * @param lon_now current position in degrees (8.1234567°, not 81234567°)
- * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
- * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
- */
-__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
-
-__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);
-
-__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
- float radius, float arc_start_bearing, float arc_sweep);
-
-__EXPORT float _wrap_180(float bearing);
-__EXPORT float _wrap_360(float bearing);
-__EXPORT float _wrap_pi(float bearing);
-__EXPORT float _wrap_2pi(float bearing);
-
-__END_DECLS
diff --git a/src/modules/systemlib/mavlink_log.c b/src/modules/systemlib/mavlink_log.c
new file mode 100644
index 000000000..f321f9ceb
--- /dev/null
+++ b/src/modules/systemlib/mavlink_log.c
@@ -0,0 +1,128 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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 mavlink_log.c
+ * MAVLink text logging.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <stdarg.h>
+
+#include <mavlink/mavlink_log.h>
+
+__EXPORT void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
+{
+ lb->size = size;
+ lb->start = 0;
+ lb->count = 0;
+ lb->elems = calloc(lb->size, sizeof(struct mavlink_logmessage));
+}
+
+__EXPORT void mavlink_logbuffer_destroy(struct mavlink_logbuffer *lb)
+{
+ lb->size = 0;
+ lb->start = 0;
+ lb->count = 0;
+ free(lb->elems);
+}
+
+__EXPORT int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb)
+{
+ return lb->count == (int)lb->size;
+}
+
+__EXPORT int mavlink_logbuffer_is_empty(struct mavlink_logbuffer *lb)
+{
+ return lb->count == 0;
+}
+
+__EXPORT void mavlink_logbuffer_write(struct mavlink_logbuffer *lb, const struct mavlink_logmessage *elem)
+{
+ int end = (lb->start + lb->count) % lb->size;
+ memcpy(&(lb->elems[end]), elem, sizeof(struct mavlink_logmessage));
+
+ if (mavlink_logbuffer_is_full(lb)) {
+ lb->start = (lb->start + 1) % lb->size; /* full, overwrite */
+
+ } else {
+ ++lb->count;
+ }
+}
+
+__EXPORT int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessage *elem)
+{
+ if (!mavlink_logbuffer_is_empty(lb)) {
+ memcpy(elem, &(lb->elems[lb->start]), sizeof(struct mavlink_logmessage));
+ lb->start = (lb->start + 1) % lb->size;
+ --lb->count;
+
+ return 0;
+
+ } else {
+ return 1;
+ }
+}
+
+__EXPORT void mavlink_logbuffer_vasprintf(struct mavlink_logbuffer *lb, int severity, const char *fmt, ...)
+{
+ va_list ap;
+ va_start(ap, fmt);
+ int end = (lb->start + lb->count) % lb->size;
+ lb->elems[end].severity = severity;
+ vsnprintf(lb->elems[end].text, sizeof(lb->elems[0].text), fmt, ap);
+ va_end(ap);
+
+ /* increase count */
+ if (mavlink_logbuffer_is_full(lb)) {
+ lb->start = (lb->start + 1) % lb->size; /* full, overwrite */
+
+ } else {
+ ++lb->count;
+ }
+}
+
+__EXPORT void mavlink_vasprintf(int _fd, int severity, const char *fmt, ...)
+{
+ va_list ap;
+ va_start(ap, fmt);
+ char text[MAVLINK_LOG_MAXLEN + 1];
+ vsnprintf(text, sizeof(text), fmt, ap);
+ va_end(ap);
+ ioctl(_fd, severity, (unsigned long)&text[0]);
+}
diff --git a/src/modules/systemlib/mixer/mixer.cpp b/src/modules/systemlib/mixer/mixer.cpp
index df0dfe838..cce46bf5f 100644
--- a/src/modules/systemlib/mixer/mixer.cpp
+++ b/src/modules/systemlib/mixer/mixer.cpp
@@ -50,6 +50,8 @@
#include <stdio.h>
#include <math.h>
#include <unistd.h>
+#include <ctype.h>
+#include <systemlib/err.h>
#include "mixer.h"
@@ -114,6 +116,33 @@ Mixer::scale_check(struct mixer_scaler_s &scaler)
return 0;
}
+const char *
+Mixer::findtag(const char *buf, unsigned &buflen, char tag)
+{
+ while (buflen >= 2) {
+ if ((buf[0] == tag) && (buf[1] == ':'))
+ return buf;
+ buf++;
+ buflen--;
+ }
+ return nullptr;
+}
+
+const char *
+Mixer::skipline(const char *buf, unsigned &buflen)
+{
+ const char *p;
+
+ /* if we can find a CR or NL in the buffer, skip up to it */
+ if ((p = (const char *)memchr(buf, '\r', buflen)) || (p = (const char *)memchr(buf, '\n', buflen))) {
+ /* skip up to it AND one beyond - could be on the NUL symbol now */
+ buflen -= (p - buf) + 1;
+ return p + 1;
+ }
+
+ return nullptr;
+}
+
/****************************************************************************/
NullMixer::NullMixer() :
@@ -142,6 +171,22 @@ NullMixer *
NullMixer::from_text(const char *buf, unsigned &buflen)
{
NullMixer *nm = nullptr;
+ const char *end = buf + buflen;
+
+ /* enforce that the mixer ends with space or a new line */
+ for (int i = buflen - 1; i >= 0; i--) {
+ if (buf[i] == '\0')
+ continue;
+
+ /* require a space or newline at the end of the buffer, fail on printable chars */
+ if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
+ /* found a line ending or space, so no split symbols / numbers. good. */
+ break;
+ } else {
+ return nm;
+ }
+
+ }
if ((buflen >= 2) && (buf[0] == 'Z') && (buf[1] == ':')) {
nm = new NullMixer;
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index bbfa130a9..1c889a811 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -128,7 +128,9 @@
#ifndef _SYSTEMLIB_MIXER_MIXER_H
#define _SYSTEMLIB_MIXER_MIXER_H value
+#include <nuttx/config.h>
#include "drivers/drv_mixer.h"
+#include "mixer_load.h"
/**
* Abstract class defining a mixer mixing zero or more inputs to
@@ -210,6 +212,24 @@ protected:
*/
static int scale_check(struct mixer_scaler_s &scaler);
+ /**
+ * Find a tag
+ *
+ * @param buf The buffer to operate on.
+ * @param buflen length of the buffer.
+ * @param tag character to search for.
+ */
+ static const char * findtag(const char *buf, unsigned &buflen, char tag);
+
+ /**
+ * Skip a line
+ *
+ * @param buf The buffer to operate on.
+ * @param buflen length of the buffer.
+ * @return 0 / OK if a line could be skipped, 1 else
+ */
+ static const char * skipline(const char *buf, unsigned &buflen);
+
private:
};
@@ -239,6 +259,11 @@ public:
void reset();
/**
+ * Count the mixers in the group.
+ */
+ unsigned count();
+
+ /**
* Adds mixers to the group based on a text description in a buffer.
*
* Mixer definitions begin with a single capital letter and a colon.
@@ -424,6 +449,7 @@ public:
HEX_PLUS, /**< hex in + configuration */
OCTA_X,
OCTA_PLUS,
+ OCTA_COX,
MAX_GEOMETRY
};
diff --git a/src/modules/systemlib/mixer/mixer_group.cpp b/src/modules/systemlib/mixer/mixer_group.cpp
index 1dbc512cd..3ed99fba0 100644
--- a/src/modules/systemlib/mixer/mixer_group.cpp
+++ b/src/modules/systemlib/mixer/mixer_group.cpp
@@ -111,6 +111,20 @@ MixerGroup::mix(float *outputs, unsigned space)
return index;
}
+unsigned
+MixerGroup::count()
+{
+ Mixer *mixer = _first;
+ unsigned index = 0;
+
+ while ((mixer != nullptr)) {
+ mixer = mixer->_next;
+ index++;
+ }
+
+ return index;
+}
+
void
MixerGroup::groups_required(uint32_t &groups)
{
@@ -170,6 +184,7 @@ MixerGroup::load_from_buf(const char *buf, unsigned &buflen)
/* only adjust buflen if parsing was successful */
buflen = resid;
+ debug("SUCCESS - buflen: %d", buflen);
} else {
/*
diff --git a/src/modules/systemlib/mixer/mixer_load.c b/src/modules/systemlib/mixer/mixer_load.c
new file mode 100644
index 000000000..a55ddf8a3
--- /dev/null
+++ b/src/modules/systemlib/mixer/mixer_load.c
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 mixer_load.c
+ *
+ * Programmable multi-channel mixer library.
+ */
+
+#include <nuttx/config.h>
+#include <string.h>
+#include <stdio.h>
+#include <ctype.h>
+
+#include "mixer_load.h"
+
+int load_mixer_file(const char *fname, char *buf, unsigned maxlen)
+{
+ FILE *fp;
+ char line[120];
+
+ /* open the mixer definition file */
+ fp = fopen(fname, "r");
+ if (fp == NULL) {
+ return 1;
+ }
+
+ /* read valid lines from the file into a buffer */
+ buf[0] = '\0';
+ for (;;) {
+
+ /* get a line, bail on error/EOF */
+ line[0] = '\0';
+ if (fgets(line, sizeof(line), fp) == NULL)
+ break;
+
+ /* if the line doesn't look like a mixer definition line, skip it */
+ if ((strlen(line) < 2) || !isupper(line[0]) || (line[1] != ':'))
+ continue;
+
+ /* compact whitespace in the buffer */
+ char *t, *f;
+ for (f = line; *f != '\0'; f++) {
+ /* scan for space characters */
+ if (*f == ' ') {
+ /* look for additional spaces */
+ t = f + 1;
+ while (*t == ' ')
+ t++;
+ if (*t == '\0') {
+ /* strip trailing whitespace */
+ *f = '\0';
+ } else if (t > (f + 1)) {
+ memmove(f + 1, t, strlen(t) + 1);
+ }
+ }
+ }
+
+ /* if the line is too long to fit in the buffer, bail */
+ if ((strlen(line) + strlen(buf) + 1) >= maxlen) {
+ return 1;
+ }
+
+ /* add the line to the buffer */
+ strcat(buf, line);
+ }
+
+ return 0;
+}
+
diff --git a/src/modules/systemlib/mixer/mixer_load.h b/src/modules/systemlib/mixer/mixer_load.h
new file mode 100644
index 000000000..4b7091d5b
--- /dev/null
+++ b/src/modules/systemlib/mixer/mixer_load.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 mixer_load.h
+ *
+ */
+
+
+#ifndef _SYSTEMLIB_MIXER_LOAD_H
+#define _SYSTEMLIB_MIXER_LOAD_H value
+
+#include <nuttx/config.h>
+
+__BEGIN_DECLS
+
+__EXPORT int load_mixer_file(const char *fname, char *buf, unsigned maxlen);
+
+__END_DECLS
+
+#endif
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 8ded0b05c..bf77795d5 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -130,7 +130,17 @@ const MultirotorMixer::Rotor _config_octa_plus[] = {
{ 1.000000, 0.000000, -1.00 },
{ -1.000000, 0.000000, -1.00 },
};
-const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
+const MultirotorMixer::Rotor _config_octa_cox[] = {
+ { -0.707107, 0.707107, 1.00 },
+ { 0.707107, 0.707107, -1.00 },
+ { 0.707107, -0.707107, 1.00 },
+ { -0.707107, -0.707107, -1.00 },
+ { 0.707107, 0.707107, 1.00 },
+ { -0.707107, 0.707107, -1.00 },
+ { -0.707107, -0.707107, 1.00 },
+ { 0.707107, -0.707107, -1.00 },
+};
+const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
&_config_quad_x[0],
&_config_quad_plus[0],
&_config_quad_v[0],
@@ -139,8 +149,9 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOME
&_config_hex_plus[0],
&_config_octa_x[0],
&_config_octa_plus[0],
+ &_config_octa_cox[0],
};
-const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
+const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
4, /* quad_x */
4, /* quad_plus */
4, /* quad_v */
@@ -149,6 +160,7 @@ const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
6, /* hex_plus */
8, /* octa_x */
8, /* octa_plus */
+ 8, /* octa_cox */
};
}
@@ -181,6 +193,23 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
char geomname[8];
int s[4];
int used;
+ const char *end = buf + buflen;
+
+ /* enforce that the mixer ends with space or a new line */
+ for (int i = buflen - 1; i >= 0; i--) {
+ if (buf[i] == '\0')
+ continue;
+
+ /* require a space or newline at the end of the buffer, fail on printable chars */
+ if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
+ /* found a line ending or space, so no split symbols / numbers. good. */
+ break;
+ } else {
+ debug("simple parser rejected: No newline / space at end of buf. (#%d/%d: 0x%02x)", i, buflen-1, buf[i]);
+ return nullptr;
+ }
+
+ }
if (sscanf(buf, "R: %s %d %d %d %d%n", geomname, &s[0], &s[1], &s[2], &s[3], &used) != 5) {
debug("multirotor parse failed on '%s'", buf);
@@ -188,11 +217,17 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
}
if (used > (int)buflen) {
- debug("multirotor spec used %d of %u", used, buflen);
+ debug("OVERFLOW: multirotor spec used %d of %u", used, buflen);
+ return nullptr;
+ }
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
return nullptr;
}
- buflen -= used;
+ debug("remaining in buf: %d, first char: %c", buflen, buf[0]);
if (!strcmp(geomname, "4+")) {
geometry = MultirotorMixer::QUAD_PLUS;
@@ -217,6 +252,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
} else if (!strcmp(geomname, "8x")) {
geometry = MultirotorMixer::OCTA_X;
+
+ } else if (!strcmp(geomname, "8c")) {
+ geometry = MultirotorMixer::OCTA_COX;
} else {
debug("unrecognised geometry '%s'", geomname);
diff --git a/src/modules/systemlib/mixer/mixer_simple.cpp b/src/modules/systemlib/mixer/mixer_simple.cpp
index 07dc5f37f..c3985b5de 100644
--- a/src/modules/systemlib/mixer/mixer_simple.cpp
+++ b/src/modules/systemlib/mixer/mixer_simple.cpp
@@ -71,44 +71,30 @@ SimpleMixer::~SimpleMixer()
free(_info);
}
-static const char *
-findtag(const char *buf, unsigned &buflen, char tag)
-{
- while (buflen >= 2) {
- if ((buf[0] == tag) && (buf[1] == ':'))
- return buf;
- buf++;
- buflen--;
- }
- return nullptr;
-}
-
-static void
-skipline(const char *buf, unsigned &buflen)
-{
- const char *p;
-
- /* if we can find a CR or NL in the buffer, skip up to it */
- if ((p = (const char *)memchr(buf, '\r', buflen)) || (p = (const char *)memchr(buf, '\n', buflen)))
- buflen -= (p - buf);
-}
-
int
SimpleMixer::parse_output_scaler(const char *buf, unsigned &buflen, mixer_scaler_s &scaler)
{
int ret;
int s[5];
+ int n = -1;
buf = findtag(buf, buflen, 'O');
- if ((buf == nullptr) || (buflen < 12))
+ if ((buf == nullptr) || (buflen < 12)) {
+ debug("output parser failed finding tag, ret: '%s'", buf);
return -1;
+ }
- if ((ret = sscanf(buf, "O: %d %d %d %d %d",
- &s[0], &s[1], &s[2], &s[3], &s[4])) != 5) {
- debug("scaler parse failed on '%s' (got %d)", buf, ret);
+ if ((ret = sscanf(buf, "O: %d %d %d %d %d %n",
+ &s[0], &s[1], &s[2], &s[3], &s[4], &n)) != 5) {
+ debug("out scaler parse failed on '%s' (got %d, consumed %d)", buf, ret, n);
+ return -1;
+ }
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
return -1;
}
- skipline(buf, buflen);
scaler.negative_scale = s[0] / 10000.0f;
scaler.positive_scale = s[1] / 10000.0f;
@@ -126,15 +112,22 @@ SimpleMixer::parse_control_scaler(const char *buf, unsigned &buflen, mixer_scale
int s[5];
buf = findtag(buf, buflen, 'S');
- if ((buf == nullptr) || (buflen < 16))
+ if ((buf == nullptr) || (buflen < 16)) {
+ debug("control parser failed finding tag, ret: '%s'", buf);
return -1;
+ }
if (sscanf(buf, "S: %u %u %d %d %d %d %d",
&u[0], &u[1], &s[0], &s[1], &s[2], &s[3], &s[4]) != 7) {
debug("control parse failed on '%s'", buf);
return -1;
}
- skipline(buf, buflen);
+
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ return -1;
+ }
control_group = u[0];
control_index = u[1];
@@ -162,7 +155,11 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c
goto out;
}
- buflen -= used;
+ buf = skipline(buf, buflen);
+ if (buf == nullptr) {
+ debug("no line ending, line is incomplete");
+ goto out;
+ }
mixinfo = (mixer_simple_s *)malloc(MIXER_SIMPLE_SIZE(inputs));
@@ -173,22 +170,27 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c
mixinfo->control_count = inputs;
- if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler))
+ if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler)) {
+ debug("simple mixer parser failed parsing out scaler tag, ret: '%s'", buf);
goto out;
+ }
for (unsigned i = 0; i < inputs; i++) {
if (parse_control_scaler(end - buflen, buflen,
mixinfo->controls[i].scaler,
mixinfo->controls[i].control_group,
- mixinfo->controls[i].control_index))
+ mixinfo->controls[i].control_index)) {
+ debug("simple mixer parser failed parsing ctrl scaler tag, ret: '%s'", buf);
goto out;
+ }
+
}
sm = new SimpleMixer(control_cb, cb_handle, mixinfo);
if (sm != nullptr) {
mixinfo = nullptr;
- debug("loaded mixer with %d inputs", inputs);
+ debug("loaded mixer with %d input(s)", inputs);
} else {
debug("could not allocate memory for mixer");
diff --git a/src/modules/systemlib/mixer/module.mk b/src/modules/systemlib/mixer/module.mk
index 4d45e1c50..fc7485e20 100644
--- a/src/modules/systemlib/mixer/module.mk
+++ b/src/modules/systemlib/mixer/module.mk
@@ -39,4 +39,5 @@ LIBNAME = mixerlib
SRCS = mixer.cpp \
mixer_group.cpp \
mixer_multirotor.cpp \
- mixer_simple.cpp
+ mixer_simple.cpp \
+ mixer_load.c
diff --git a/src/modules/systemlib/mixer/multi_tables b/src/modules/systemlib/mixer/multi_tables
index 683c63040..050bf2f47 100755
--- a/src/modules/systemlib/mixer/multi_tables
+++ b/src/modules/systemlib/mixer/multi_tables
@@ -74,7 +74,18 @@ set octa_plus {
90 CW
}
-set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus}
+set octa_cox {
+ 45 CCW
+ -45 CW
+ -135 CCW
+ 135 CW
+ -45 CCW
+ 45 CW
+ 135 CCW
+ -135 CW
+}
+
+set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus octa_cox}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index b470c1227..843cda722 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -45,7 +45,8 @@ SRCS = err.c \
getopt_long.c \
up_cxxinitialize.c \
pid/pid.c \
- geo/geo.c \
systemlib.c \
airspeed.c \
- system_params.c
+ system_params.c \
+ mavlink_log.c \
+ rc_check.c
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index 69a9bdf9b..398657dd7 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -48,6 +48,7 @@
#include <unistd.h>
#include <systemlib/err.h>
#include <errno.h>
+#include <semaphore.h>
#include <sys/stat.h>
@@ -95,18 +96,20 @@ ORB_DEFINE(parameter_update, struct parameter_update_s);
/** parameter update topic handle */
static orb_advert_t param_topic = -1;
+static sem_t param_sem = { .semcount = 1 };
+
/** lock the parameter store */
static void
param_lock(void)
{
- /* XXX */
+ //do {} while (sem_wait(&param_sem) != 0);
}
/** unlock the parameter store */
static void
param_unlock(void)
{
- /* XXX */
+ //sem_post(&param_sem);
}
/** assert that the parameter store is locked */
@@ -505,27 +508,63 @@ param_get_default_file(void)
int
param_save_default(void)
{
- /* delete the file in case it exists */
- unlink(param_get_default_file());
+ int res;
+ int fd;
- /* create the file */
- int fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL);
+ const char *filename = param_get_default_file();
+ const char *filename_tmp = malloc(strlen(filename) + 5);
+ sprintf(filename_tmp, "%s.tmp", filename);
- if (fd < 0) {
- warn("opening '%s' for writing failed", param_get_default_file());
- return -1;
+ /* delete temp file if exist */
+ res = unlink(filename_tmp);
+
+ if (res != OK && errno == ENOENT)
+ res = OK;
+
+ if (res != OK)
+ warn("failed to delete temp file: %s", filename_tmp);
+
+ if (res == OK) {
+ /* write parameters to temp file */
+ fd = open(filename_tmp, O_WRONLY | O_CREAT | O_EXCL);
+
+ if (fd < 0) {
+ warn("failed to open temp file: %s", filename_tmp);
+ res = ERROR;
+ }
+
+ if (res == OK) {
+ res = param_export(fd, false);
+
+ if (res != OK)
+ warnx("failed to write parameters to file: %s", filename_tmp);
+ }
+
+ close(fd);
}
- int result = param_export(fd, false);
- close(fd);
+ if (res == OK) {
+ /* delete parameters file */
+ res = unlink(filename);
- if (result != 0) {
- warn("error exporting parameters to '%s'", param_get_default_file());
- unlink(param_get_default_file());
- return -2;
+ if (res != OK && errno == ENOENT)
+ res = OK;
+
+ if (res != OK)
+ warn("failed to delete parameters file: %s", filename);
}
- return 0;
+ if (res == OK) {
+ /* rename temp file to parameters */
+ res = rename(filename_tmp, filename);
+
+ if (res != OK)
+ warn("failed to rename %s to %s", filename_tmp, filename);
+ }
+
+ free(filename_tmp);
+
+ return res;
}
/**
diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c
index 3c1e10287..bf84b7945 100644
--- a/src/modules/systemlib/perf_counter.c
+++ b/src/modules/systemlib/perf_counter.c
@@ -321,6 +321,32 @@ perf_print_counter(perf_counter_t handle)
}
}
+uint64_t
+perf_event_count(perf_counter_t handle)
+{
+ if (handle == NULL)
+ return 0;
+
+ switch (handle->type) {
+ case PC_COUNT:
+ return ((struct perf_ctr_count *)handle)->event_count;
+
+ case PC_ELAPSED: {
+ struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
+ return pce->event_count;
+ }
+
+ case PC_INTERVAL: {
+ struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
+ return pci->event_count;
+ }
+
+ default:
+ break;
+ }
+ return 0;
+}
+
void
perf_print_all(void)
{
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index 4cd8b67a1..e1e3cbe95 100644
--- a/src/modules/systemlib/perf_counter.h
+++ b/src/modules/systemlib/perf_counter.h
@@ -135,6 +135,14 @@ __EXPORT extern void perf_print_all(void);
*/
__EXPORT extern void perf_reset_all(void);
+/**
+ * Return current event_count
+ *
+ * @param handle The counter returned from perf_alloc.
+ * @return event_count
+ */
+__EXPORT extern uint64_t perf_event_count(perf_counter_t handle);
+
__END_DECLS
#endif
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 4996a8f66..77c952f52 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -51,6 +51,8 @@
#include "pid.h"
#include <math.h>
+#define SIGMA 0.000001f
+
__EXPORT void pid_init(PID_t *pid, float kp, float ki, float kd, float intmax,
float limit, uint8_t mode, float dt_min)
{
@@ -165,20 +167,26 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
d = 0.0f;
}
- // Calculate the error integral and check for saturation
- i = pid->integral + (error * dt);
+ if (pid->ki > 0.0f) {
+ // Calculate the error integral and check for saturation
+ i = pid->integral + (error * dt);
- if (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit ||
- fabsf(i) > pid->intmax) {
- i = pid->integral; // If saturated then do not update integral value
- pid->saturated = 1;
+ if ((pid->limit > SIGMA && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) ||
+ fabsf(i) > pid->intmax) {
+ i = pid->integral; // If saturated then do not update integral value
+ pid->saturated = 1;
- } else {
- if (!isfinite(i)) {
- i = 0.0f;
+ } else {
+ if (!isfinite(i)) {
+ i = 0.0f;
+ }
+
+ pid->integral = i;
+ pid->saturated = 0;
}
- pid->integral = i;
+ } else {
+ i = 0.0f;
pid->saturated = 0;
}
@@ -186,11 +194,13 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
float output = (error * pid->kp) + (i * pid->ki) + (d * pid->kd);
if (isfinite(output)) {
- if (output > pid->limit) {
- output = pid->limit;
+ if (pid->limit > SIGMA) {
+ if (output > pid->limit) {
+ output = pid->limit;
- } else if (output < -pid->limit) {
- output = -pid->limit;
+ } else if (output < -pid->limit) {
+ output = -pid->limit;
+ }
}
pid->last_output = output;
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.c b/src/modules/systemlib/pwm_limit/pwm_limit.c
new file mode 100644
index 000000000..cac3dc82a
--- /dev/null
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.c
@@ -0,0 +1,133 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: 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 pwm_limit.c
+ *
+ * Lib to limit PWM output
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#include "pwm_limit.h"
+#include <math.h>
+#include <stdbool.h>
+#include <drivers/drv_hrt.h>
+
+void pwm_limit_init(pwm_limit_t *limit)
+{
+ limit->state = LIMIT_STATE_OFF;
+ limit->time_armed = 0;
+ return;
+}
+
+void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, float *output, uint16_t *effective_pwm, pwm_limit_t *limit)
+{
+ /* first evaluate state changes */
+ switch (limit->state) {
+ case LIMIT_STATE_OFF:
+ if (armed)
+ limit->state = LIMIT_STATE_RAMP;
+ limit->time_armed = hrt_absolute_time();
+ break;
+ case LIMIT_STATE_INIT:
+ if (!armed)
+ limit->state = LIMIT_STATE_OFF;
+ else if (hrt_absolute_time() - limit->time_armed >= INIT_TIME_US)
+ limit->state = LIMIT_STATE_RAMP;
+ break;
+ case LIMIT_STATE_RAMP:
+ if (!armed)
+ limit->state = LIMIT_STATE_OFF;
+ else if (hrt_absolute_time() - limit->time_armed >= INIT_TIME_US + RAMP_TIME_US)
+ limit->state = LIMIT_STATE_ON;
+ break;
+ case LIMIT_STATE_ON:
+ if (!armed)
+ limit->state = LIMIT_STATE_OFF;
+ break;
+ default:
+ break;
+ }
+
+ unsigned progress;
+ uint16_t temp_pwm;
+
+ /* then set effective_pwm based on state */
+ switch (limit->state) {
+ case LIMIT_STATE_OFF:
+ case LIMIT_STATE_INIT:
+ for (unsigned i=0; i<num_channels; i++) {
+ effective_pwm[i] = disarmed_pwm[i];
+ output[i] = 0.0f;
+ }
+ break;
+ case LIMIT_STATE_RAMP:
+
+ progress = (hrt_absolute_time() - INIT_TIME_US - limit->time_armed)*10000 / RAMP_TIME_US;
+ for (unsigned i=0; i<num_channels; i++) {
+
+ uint16_t ramp_min_pwm;
+
+ /* if a disarmed pwm value was set, blend between disarmed and min */
+ if (disarmed_pwm[i] > 0) {
+
+ /* safeguard against overflows */
+ uint16_t disarmed = disarmed_pwm[i];
+ if (disarmed > min_pwm[i])
+ disarmed = min_pwm[i];
+
+ uint16_t disarmed_min_diff = min_pwm[i] - disarmed;
+ ramp_min_pwm = disarmed + (disarmed_min_diff * progress) / 10000;
+ } else {
+
+ /* no disarmed pwm value set, choose min pwm */
+ ramp_min_pwm = min_pwm[i];
+ }
+
+ effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
+ output[i] = (float)progress/10000.0f * output[i];
+ }
+ break;
+ case LIMIT_STATE_ON:
+ for (unsigned i=0; i<num_channels; i++) {
+ effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
+ /* effective_output stays the same */
+ }
+ break;
+ default:
+ break;
+ }
+ return;
+}
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.h b/src/modules/systemlib/pwm_limit/pwm_limit.h
new file mode 100644
index 000000000..9974770be
--- /dev/null
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: 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 pwm_limit.h
+ *
+ * Lib to limit PWM output
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#ifndef PWM_LIMIT_H_
+#define PWM_LIMIT_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/*
+ * time for the ESCs to initialize
+ * (this is not actually needed if PWM is sent right after boot)
+ */
+#define INIT_TIME_US 500000
+/*
+ * time to slowly ramp up the ESCs
+ */
+#define RAMP_TIME_US 2500000
+
+typedef struct {
+ enum {
+ LIMIT_STATE_OFF = 0,
+ LIMIT_STATE_INIT,
+ LIMIT_STATE_RAMP,
+ LIMIT_STATE_ON
+ } state;
+ uint64_t time_armed;
+} pwm_limit_t;
+
+__BEGIN_DECLS
+
+__EXPORT void pwm_limit_init(pwm_limit_t *limit);
+
+__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
+
+__END_DECLS
+
+#endif /* PWM_LIMIT_H_ */
diff --git a/src/modules/systemlib/rc_check.c b/src/modules/systemlib/rc_check.c
new file mode 100644
index 000000000..b4350cc24
--- /dev/null
+++ b/src/modules/systemlib/rc_check.c
@@ -0,0 +1,151 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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_check.c
+ *
+ * RC calibration check
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <fcntl.h>
+
+#include <systemlib/rc_check.h>
+#include <systemlib/param/param.h>
+#include <mavlink/mavlink_log.h>
+#include <uORB/topics/rc_channels.h>
+
+int rc_calibration_check(int mavlink_fd) {
+
+ char nbuf[20];
+ param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
+ _parameter_handles_rev, _parameter_handles_dz;
+
+ float param_min, param_max, param_trim, param_rev, param_dz;
+
+ /* first check channel mappings */
+ /* check which map param applies */
+ // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
+ // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
+ // /* give system time to flush error message in case there are more */
+ // usleep(100000);
+ // count++;
+ // }
+
+ int channel_fail_count = 0;
+
+ for (int i = 0; i < RC_CHANNELS_MAX; i++) {
+ /* should the channel be enabled? */
+ uint8_t count = 0;
+
+ /* min values */
+ sprintf(nbuf, "RC%d_MIN", i + 1);
+ _parameter_handles_min = param_find(nbuf);
+ param_get(_parameter_handles_min, &param_min);
+
+ /* trim values */
+ sprintf(nbuf, "RC%d_TRIM", i + 1);
+ _parameter_handles_trim = param_find(nbuf);
+ param_get(_parameter_handles_trim, &param_trim);
+
+ /* max values */
+ sprintf(nbuf, "RC%d_MAX", i + 1);
+ _parameter_handles_max = param_find(nbuf);
+ param_get(_parameter_handles_max, &param_max);
+
+ /* channel reverse */
+ sprintf(nbuf, "RC%d_REV", i + 1);
+ _parameter_handles_rev = param_find(nbuf);
+ param_get(_parameter_handles_rev, &param_rev);
+
+ /* channel deadzone */
+ sprintf(nbuf, "RC%d_DZ", i + 1);
+ _parameter_handles_dz = param_find(nbuf);
+ param_get(_parameter_handles_dz, &param_dz);
+
+ /* assert min..center..max ordering */
+ if (param_min < 500) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MIN < 500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_max > 2500) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAX > 2500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_trim < param_min) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM < MIN (%d/%d)", i+1, (int)param_trim, (int)param_min);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+ if (param_trim > param_max) {
+ count++;
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM > MAX (%d/%d)", i+1, (int)param_trim, (int)param_max);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ }
+
+ /* assert deadzone is sane */
+ if (param_dz > 500) {
+ mavlink_log_critical(mavlink_fd, "ERR: RC_%d_DZ > 500", i+1);
+ /* give system time to flush error message in case there are more */
+ usleep(100000);
+ count++;
+ }
+
+ /* check which map param applies */
+ // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
+ // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
+ // /* give system time to flush error message in case there are more */
+ // usleep(100000);
+ // count++;
+ // }
+
+ /* sanity checks pass, enable channel */
+ if (count) {
+ mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ warnx(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ usleep(100000);
+ }
+
+ channel_fail_count += count;
+ }
+
+ return channel_fail_count;
+}
diff --git a/src/modules/systemlib/rc_check.h b/src/modules/systemlib/rc_check.h
new file mode 100644
index 000000000..e70b83cce
--- /dev/null
+++ b/src/modules/systemlib/rc_check.h
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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_check.h
+ *
+ * RC calibration check
+ */
+
+#pragma once
+
+ __BEGIN_DECLS
+
+/**
+ * Check the RC calibration
+ *
+ * @return 0 / OK if RC calibration is ok, index + 1 of the first
+ * channel that failed else (so 1 == first channel failed)
+ */
+__EXPORT int rc_calibration_check(int mavlink_fd);
+
+__END_DECLS
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index 3283aad8a..57a751e1c 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -43,13 +43,29 @@
#include <fcntl.h>
#include <sched.h>
#include <signal.h>
-#include <sys/stat.h>
#include <unistd.h>
#include <float.h>
#include <string.h>
+#include <sys/stat.h>
+#include <sys/types.h>
+
+#include <stm32_pwr.h>
+
#include "systemlib.h"
+void
+systemreset(bool to_bootloader)
+{
+ if (to_bootloader) {
+ stm32_pwr_enablebkp();
+
+ /* XXX wow, this is evil - write a magic number into backup register zero */
+ *(uint32_t *)0x40002850 = 0xb007b007;
+ }
+ up_systemreset();
+}
+
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
void killall()
diff --git a/src/modules/systemlib/systemlib.h b/src/modules/systemlib/systemlib.h
index 0194b5e52..3728f2067 100644
--- a/src/modules/systemlib/systemlib.h
+++ b/src/modules/systemlib/systemlib.h
@@ -42,11 +42,11 @@
#include <float.h>
#include <stdint.h>
-/** Reboots the board */
-extern void up_systemreset(void) noreturn_function;
-
__BEGIN_DECLS
+/** Reboots the board */
+__EXPORT void systemreset(bool to_bootloader) noreturn_function;
+
/** Sends SIGUSR1 to all processes */
__EXPORT void killall(void);