Merge branch 'master' into yaw_offset_limit

This commit is contained in:
Anton Babushkin 2014-05-15 10:23:14 +02:00
commit 7ef3c24637
51 changed files with 231 additions and 116 deletions

View File

@ -11,6 +11,4 @@ then
param set NAV_RTL_ALT 100 param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1 param set NAV_RTL_LAND_T -1
param set NAV_ACCEPT_RAD 50 param set NAV_ACCEPT_RAD 50
param set RC_SCALE_ROLL 1
param set RC_SCALE_PITCH 1
fi fi

View File

@ -8,7 +8,7 @@ then
if ver hwcmp PX4FMU_V1 if ver hwcmp PX4FMU_V1
then then
echo "Start sdlog2 at 50Hz" echo "Start sdlog2 at 50Hz"
sdlog2 start -r 50 -a -b 8 -t sdlog2 start -r 50 -a -b 5 -t
else else
echo "Start sdlog2 at 200Hz" echo "Start sdlog2 at 200Hz"
sdlog2 start -r 200 -a -b 16 -t sdlog2 start -r 200 -a -b 16 -t

View File

@ -3,16 +3,20 @@
# USB MAVLink start # USB MAVLink start
# #
echo "Starting MAVLink on this USB console"
mavlink start -r 10000 -d /dev/ttyACM0 mavlink start -r 10000 -d /dev/ttyACM0
# Enable a number of interesting streams we want via USB # Enable a number of interesting streams we want via USB
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10 mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
usleep 100000
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10 mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
usleep 100000
mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20 mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20 mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30 mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 10 usleep 100000
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
usleep 100000
# Exit shell to make it available to MAVLink # Exit shell to make it available to MAVLink
exit exit

View File

@ -4,3 +4,5 @@
MODULE_COMMAND = fmu MODULE_COMMAND = fmu
SRCS = fmu.cpp SRCS = fmu.cpp
MODULE_STACKSIZE = 1200

View File

@ -44,3 +44,5 @@ SRCS = px4io.cpp \
# XXX prune to just get UART registers # XXX prune to just get UART registers
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
MODULE_STACKSIZE = 1200

View File

@ -529,6 +529,11 @@ PX4IO::~PX4IO()
if (_interface != nullptr) if (_interface != nullptr)
delete _interface; delete _interface;
/* deallocate perfs */
perf_free(_perf_update);
perf_free(_perf_write);
perf_free(_perf_chan_count);
g_dev = nullptr; g_dev = nullptr;
} }

View File

@ -39,3 +39,5 @@ MODULE_COMMAND = ex_fixedwing_control
SRCS = main.c \ SRCS = main.c \
params.c params.c
MODULE_STACKSIZE = 1200

View File

@ -38,3 +38,5 @@
MODULE_COMMAND = px4_daemon_app MODULE_COMMAND = px4_daemon_app
SRCS = px4_daemon_app.c SRCS = px4_daemon_app.c
MODULE_STACKSIZE = 1200

View File

@ -98,7 +98,7 @@ int px4_daemon_app_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("daemon", daemon_task = task_spawn_cmd("daemon",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT, SCHED_PRIORITY_DEFAULT,
4096, 2000,
px4_daemon_thread_main, px4_daemon_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL); (argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0); exit(0);

View File

@ -38,3 +38,5 @@
MODULE_COMMAND = px4_mavlink_debug MODULE_COMMAND = px4_mavlink_debug
SRCS = px4_mavlink_debug.c SRCS = px4_mavlink_debug.c
MODULE_STACKSIZE = 2000

View File

@ -1,8 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (C) 2012 PX4 Development Team. All rights reserved. * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
* Author: Tobias Naegeli <naegelit@student.ethz.ch>
* Lorenz Meier <lm@inf.ethz.ch>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -34,9 +32,12 @@
****************************************************************************/ ****************************************************************************/
/* /*
* @file attitude_estimator_ekf_main.c * @file attitude_estimator_ekf_main.cpp
* *
* Extended Kalman Filter for Attitude Estimation. * Extended Kalman Filter for Attitude Estimation.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
*/ */
#include <nuttx/config.h> #include <nuttx/config.h>
@ -111,7 +112,7 @@ usage(const char *reason)
* Makefile does only apply to this management task. * Makefile does only apply to this management task.
* *
* The actual stack size should be set in the call * The actual stack size should be set in the call
* to task_create(). * to task_spawn_cmd().
*/ */
int attitude_estimator_ekf_main(int argc, char *argv[]) int attitude_estimator_ekf_main(int argc, char *argv[])
{ {

View File

@ -50,3 +50,5 @@ SRCS = attitude_estimator_ekf_main.cpp \
codegen/rtGetNaN.c \ codegen/rtGetNaN.c \
codegen/norm.c \ codegen/norm.c \
codegen/cross.c codegen/cross.c
MODULE_STACKSIZE = 1200

View File

@ -1,8 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (C) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: Hyon Lim <limhyon@gmail.com>
* Anton Babushkin <anton.babushkin@me.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -36,6 +34,9 @@
/* /*
* @file attitude_estimator_so3_main.cpp * @file attitude_estimator_so3_main.cpp
* *
* @author Hyon Lim <limhyon@gmail.com>
* @author Anton Babushkin <anton.babushkin@me.com>
*
* Implementation of nonlinear complementary filters on the SO(3). * Implementation of nonlinear complementary filters on the SO(3).
* This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer. * This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer.
* Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix. * Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix.
@ -131,7 +132,7 @@ usage(const char *reason)
* Makefile does only apply to this management task. * Makefile does only apply to this management task.
* *
* The actual stack size should be set in the call * The actual stack size should be set in the call
* to task_create(). * to task_spawn_cmd().
*/ */
int attitude_estimator_so3_main(int argc, char *argv[]) int attitude_estimator_so3_main(int argc, char *argv[])
{ {

View File

@ -6,3 +6,5 @@ MODULE_COMMAND = attitude_estimator_so3
SRCS = attitude_estimator_so3_main.cpp \ SRCS = attitude_estimator_so3_main.cpp \
attitude_estimator_so3_params.c attitude_estimator_so3_params.c
MODULE_STACKSIZE = 1200

View File

@ -249,7 +249,7 @@ int commander_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("commander", daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40, SCHED_PRIORITY_MAX - 40,
3000, 2950,
commander_thread_main, commander_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL); (argv) ? (const char **)&argv[2] : (const char **)NULL);
@ -743,7 +743,7 @@ int commander_thread_main(int argc, char *argv[])
pthread_attr_t commander_low_prio_attr; pthread_attr_t commander_low_prio_attr;
pthread_attr_init(&commander_low_prio_attr); pthread_attr_init(&commander_low_prio_attr);
pthread_attr_setstacksize(&commander_low_prio_attr, 2992); pthread_attr_setstacksize(&commander_low_prio_attr, 2900);
struct sched_param param; struct sched_param param;
(void)pthread_attr_getschedparam(&commander_low_prio_attr, &param); (void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);

View File

@ -72,7 +72,7 @@ int do_mag_calibration(int mavlink_fd)
uint64_t calibration_interval = 45 * 1000 * 1000; uint64_t calibration_interval = 45 * 1000 * 1000;
/* maximum 500 values */ /* maximum 500 values */
const unsigned int calibration_maxcount = 500; const unsigned int calibration_maxcount = 240;
unsigned int calibration_counter; unsigned int calibration_counter;
struct mag_scale mscale_null = { struct mag_scale mscale_null = {
@ -121,6 +121,20 @@ int do_mag_calibration(int mavlink_fd)
if (x == NULL || y == NULL || z == NULL) { if (x == NULL || y == NULL || z == NULL) {
mavlink_log_critical(mavlink_fd, "ERROR: out of memory"); mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
/* clean up */
if (x != NULL) {
free(x);
}
if (y != NULL) {
free(y);
}
if (z != NULL) {
free(z);
}
res = ERROR; res = ERROR;
return res; return res;
} }

View File

@ -47,3 +47,7 @@ SRCS = commander.cpp \
baro_calibration.cpp \ baro_calibration.cpp \
rc_calibration.cpp \ rc_calibration.cpp \
airspeed_calibration.cpp airspeed_calibration.cpp
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os

View File

@ -1,10 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
* Author: Jean Cyr
* Lorenz Meier
* Julian Oes
* Thomas Gubler
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -37,6 +33,11 @@
/** /**
* @file dataman.c * @file dataman.c
* DATAMANAGER driver. * DATAMANAGER driver.
*
* @author Jean Cyr
* @author Lorenz Meier
* @author Julian Oes
* @author Thomas Gubler
*/ */
#include <nuttx/config.h> #include <nuttx/config.h>
@ -62,7 +63,7 @@ __EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t
__EXPORT int dm_clear(dm_item_t item); __EXPORT int dm_clear(dm_item_t item);
__EXPORT int dm_restart(dm_reset_reason restart_type); __EXPORT int dm_restart(dm_reset_reason restart_type);
/* Types of function calls supported by the worker task */ /** Types of function calls supported by the worker task */
typedef enum { typedef enum {
dm_write_func = 0, dm_write_func = 0,
dm_read_func, dm_read_func,
@ -71,11 +72,12 @@ typedef enum {
dm_number_of_funcs dm_number_of_funcs
} dm_function_t; } dm_function_t;
/* Work task work item */ /** Work task work item */
typedef struct { typedef struct {
sq_entry_t link; /**< list linkage */ sq_entry_t link; /**< list linkage */
sem_t wait_sem; sem_t wait_sem;
dm_function_t func; unsigned char first;
unsigned char func;
ssize_t result; ssize_t result;
union { union {
struct { struct {
@ -100,6 +102,8 @@ typedef struct {
}; };
} work_q_item_t; } work_q_item_t;
const size_t k_work_item_allocation_chunk_size = 8;
/* Usage statistics */ /* Usage statistics */
static unsigned g_func_counts[dm_number_of_funcs]; static unsigned g_func_counts[dm_number_of_funcs];
@ -177,9 +181,23 @@ create_work_item(void)
unlock_queue(&g_free_q); unlock_queue(&g_free_q);
/* If we there weren't any free items then obtain memory for a new one */ /* If we there weren't any free items then obtain memory for a new ones */
if (item == NULL) if (item == NULL) {
item = (work_q_item_t *)malloc(sizeof(work_q_item_t)); item = (work_q_item_t *)malloc(k_work_item_allocation_chunk_size * sizeof(work_q_item_t));
if (item) {
item->first = 1;
lock_queue(&g_free_q);
for (int i = 1; i < k_work_item_allocation_chunk_size; i++) {
(item + i)->first = 0;
sq_addfirst(&(item + i)->link, &(g_free_q.q));
}
/* Update the queue size and potentially the maximum queue size */
g_free_q.size += k_work_item_allocation_chunk_size - 1;
if (g_free_q.size > g_free_q.max_size)
g_free_q.max_size = g_free_q.size;
unlock_queue(&g_free_q);
}
}
/* If we got one then lock the item*/ /* If we got one then lock the item*/
if (item) if (item)
@ -411,7 +429,7 @@ _clear(dm_item_t item)
return result; return result;
} }
/* Tell the data manager about the type of the last reset */ /** Tell the data manager about the type of the last reset */
static int static int
_restart(dm_reset_reason reason) _restart(dm_reset_reason reason)
{ {
@ -480,7 +498,7 @@ _restart(dm_reset_reason reason)
return result; return result;
} }
/* write to the data manager file */ /** Write to the data manager file */
__EXPORT ssize_t __EXPORT ssize_t
dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count) dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
{ {
@ -505,7 +523,7 @@ dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const
return (ssize_t)enqueue_work_item_and_wait_for_result(work); return (ssize_t)enqueue_work_item_and_wait_for_result(work);
} }
/* Retrieve from the data manager file */ /** Retrieve from the data manager file */
__EXPORT ssize_t __EXPORT ssize_t
dm_read(dm_item_t item, unsigned char index, void *buf, size_t count) dm_read(dm_item_t item, unsigned char index, void *buf, size_t count)
{ {
@ -717,7 +735,7 @@ task_main(int argc, char *argv[])
for (;;) { for (;;) {
if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == NULL) if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == NULL)
break; break;
if (work->first)
free(work); free(work);
} }
@ -736,7 +754,7 @@ start(void)
sem_init(&g_init_sema, 1, 0); sem_init(&g_init_sema, 1, 0);
/* start the worker thread */ /* start the worker thread */
if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, NULL)) <= 0) { if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2000, task_main, NULL)) <= 0) {
warn("task start failed"); warn("task start failed");
return -1; return -1;
} }

View File

@ -1,6 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -46,7 +46,7 @@
extern "C" { extern "C" {
#endif #endif
/* Types of items that the data manager can store */ /** Types of items that the data manager can store */
typedef enum { typedef enum {
DM_KEY_SAFE_POINTS = 0, /* Safe points coordinates, safe point 0 is home point */ DM_KEY_SAFE_POINTS = 0, /* Safe points coordinates, safe point 0 is home point */
DM_KEY_FENCE_POINTS, /* Fence vertex coordinates */ DM_KEY_FENCE_POINTS, /* Fence vertex coordinates */
@ -56,7 +56,7 @@ extern "C" {
DM_KEY_NUM_KEYS /* Total number of item types defined */ DM_KEY_NUM_KEYS /* Total number of item types defined */
} dm_item_t; } dm_item_t;
/* The maximum number of instances for each item type */ /** The maximum number of instances for each item type */
enum { enum {
DM_KEY_SAFE_POINTS_MAX = 8, DM_KEY_SAFE_POINTS_MAX = 8,
DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES, DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES,
@ -65,24 +65,24 @@ extern "C" {
DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED
}; };
/* Data persistence levels */ /** Data persistence levels */
typedef enum { typedef enum {
DM_PERSIST_POWER_ON_RESET = 0, /* Data survives all resets */ DM_PERSIST_POWER_ON_RESET = 0, /* Data survives all resets */
DM_PERSIST_IN_FLIGHT_RESET, /* Data survives in-flight resets only */ DM_PERSIST_IN_FLIGHT_RESET, /* Data survives in-flight resets only */
DM_PERSIST_VOLATILE /* Data does not survive resets */ DM_PERSIST_VOLATILE /* Data does not survive resets */
} dm_persitence_t; } dm_persitence_t;
/* The reason for the last reset */ /** The reason for the last reset */
typedef enum { typedef enum {
DM_INIT_REASON_POWER_ON = 0, /* Data survives resets */ DM_INIT_REASON_POWER_ON = 0, /* Data survives resets */
DM_INIT_REASON_IN_FLIGHT, /* Data survives in-flight resets only */ DM_INIT_REASON_IN_FLIGHT, /* Data survives in-flight resets only */
DM_INIT_REASON_VOLATILE /* Data does not survive reset */ DM_INIT_REASON_VOLATILE /* Data does not survive reset */
} dm_reset_reason; } dm_reset_reason;
/* Maximum size in bytes of a single item instance */ /** Maximum size in bytes of a single item instance */
#define DM_MAX_DATA_SIZE 124 #define DM_MAX_DATA_SIZE 124
/* Retrieve from the data manager store */ /** Retrieve from the data manager store */
__EXPORT ssize_t __EXPORT ssize_t
dm_read( dm_read(
dm_item_t item, /* The item type to retrieve */ dm_item_t item, /* The item type to retrieve */
@ -91,7 +91,7 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */ size_t buflen /* Length in bytes of data to retrieve */
); );
/* write to the data manager store */ /** write to the data manager store */
__EXPORT ssize_t __EXPORT ssize_t
dm_write( dm_write(
dm_item_t item, /* The item type to store */ dm_item_t item, /* The item type to store */
@ -101,13 +101,13 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */ size_t buflen /* Length in bytes of data to retrieve */
); );
/* Erase all items of this type */ /** Erase all items of this type */
__EXPORT int __EXPORT int
dm_clear( dm_clear(
dm_item_t item /* The item type to clear */ dm_item_t item /* The item type to clear */
); );
/* Tell the data manager about the type of the last reset */ /** Tell the data manager about the type of the last reset */
__EXPORT int __EXPORT int
dm_restart( dm_restart(
dm_reset_reason restart_type /* The last reset type */ dm_reset_reason restart_type /* The last reset type */

View File

@ -38,3 +38,5 @@
MODULE_COMMAND = dataman MODULE_COMMAND = dataman
SRCS = dataman.c SRCS = dataman.c
MODULE_STACKSIZE = 1200

View File

@ -1523,6 +1523,8 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
void void
Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg) Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg)
{ {
uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg); uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len); mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len);
@ -2193,7 +2195,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf, task_spawn_cmd(buf,
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT, SCHED_PRIORITY_DEFAULT,
2048, 2000,
(main_t)&Mavlink::start_helper, (main_t)&Mavlink::start_helper,
(const char **)argv); (const char **)argv);

View File

@ -237,7 +237,6 @@ private:
orb_advert_t _mission_pub; orb_advert_t _mission_pub;
struct mission_s mission; struct mission_s mission;
uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
MAVLINK_MODE _mode; MAVLINK_MODE _mode;
uint8_t _mavlink_wpm_comp_id; uint8_t _mavlink_wpm_comp_id;

View File

@ -48,3 +48,5 @@ SRCS += mavlink_main.cpp \
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MAXOPTIMIZATION = -Os MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1024

View File

@ -1,9 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
* Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -35,9 +32,13 @@
****************************************************************************/ ****************************************************************************/
/** /**
* @file mc_att_control_main.c * @file mc_att_control_main.cpp
* Multicopter attitude controller. * Multicopter attitude controller.
* *
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*
* The controller has two loops: P loop for angular error and PD loop for angular rate error. * The controller has two loops: P loop for angular error and PD loop for angular rate error.
* Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch. * Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch.
* For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw, * For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw,
@ -825,7 +826,7 @@ MulticopterAttitudeControl::start()
_control_task = task_spawn_cmd("mc_att_control", _control_task = task_spawn_cmd("mc_att_control",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
2048, 2000,
(main_t)&MulticopterAttitudeControl::task_main_trampoline, (main_t)&MulticopterAttitudeControl::task_main_trampoline,
nullptr); nullptr);

View File

@ -1,9 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
* Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -37,6 +34,10 @@
/** /**
* @file mc_att_control_params.c * @file mc_att_control_params.c
* Parameters for multicopter attitude controller. * Parameters for multicopter attitude controller.
*
* @author Tobias Naegeli <naegelit@student.ethz.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*/ */
#include <systemlib/param/param.h> #include <systemlib/param/param.h>

View File

@ -1062,7 +1062,7 @@ MulticopterPositionControl::start()
_control_task = task_spawn_cmd("mc_pos_control", _control_task = task_spawn_cmd("mc_pos_control",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
2048, 2000,
(main_t)&MulticopterPositionControl::task_main_trampoline, (main_t)&MulticopterPositionControl::task_main_trampoline,
nullptr); nullptr);

View File

@ -35,6 +35,8 @@
/** /**
* @file mc_pos_control_params.c * @file mc_pos_control_params.c
* Multicopter position controller parameters. * Multicopter position controller parameters.
*
* @author Anton Babushkin <anton.babushkin@me.com>
*/ */
#include <systemlib/param/param.h> #include <systemlib/param/param.h>

View File

@ -1,8 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Jean Cyr <jean.m.cyr@gmail.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -35,6 +33,9 @@
/** /**
* @file geofence.cpp * @file geofence.cpp
* Provides functions for handling the geofence * Provides functions for handling the geofence
*
* @author Jean Cyr <jean.m.cyr@gmail.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
*/ */
#include "geofence.h" #include "geofence.h"

View File

@ -1,8 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Jean Cyr <jean.m.cyr@gmail.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -35,6 +33,9 @@
/** /**
* @file geofence.h * @file geofence.h
* Provides functions for handling the geofence * Provides functions for handling the geofence
*
* @author Jean Cyr <jean.m.cyr@gmail.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
*/ */
#ifndef GEOFENCE_H_ #ifndef GEOFENCE_H_

View File

@ -1,7 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions

View File

@ -1,8 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -35,6 +33,9 @@
/** /**
* @file mission_feasibility_checker.cpp * @file mission_feasibility_checker.cpp
* Provides checks if mission is feasible given the navigation capabilities * Provides checks if mission is feasible given the navigation capabilities
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/ */
#include "mission_feasibility_checker.h" #include "mission_feasibility_checker.h"

View File

@ -1,8 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -35,7 +33,11 @@
/** /**
* @file mission_feasibility_checker.h * @file mission_feasibility_checker.h
* Provides checks if mission is feasible given the navigation capabilities * Provides checks if mission is feasible given the navigation capabilities
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/ */
#ifndef MISSION_FEASIBILITY_CHECKER_H_ #ifndef MISSION_FEASIBILITY_CHECKER_H_
#define MISSION_FEASIBILITY_CHECKER_H_ #define MISSION_FEASIBILITY_CHECKER_H_

View File

@ -45,3 +45,5 @@ SRCS = navigator_main.cpp \
geofence_params.c geofence_params.c
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200

View File

@ -1,10 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
* @author Jean Cyr <jean.m.cyr@gmail.com>
* @author Julian Oes <joes@student.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -35,7 +31,7 @@
* *
****************************************************************************/ ****************************************************************************/
/** /**
* @file navigator_main.c * @file navigator_main.cpp
* Implementation of the main navigation state machine. * Implementation of the main navigation state machine.
* *
* Handles missions, geo fencing and failsafe navigation behavior. * Handles missions, geo fencing and failsafe navigation behavior.
@ -852,7 +848,7 @@ Navigator::start()
_navigator_task = task_spawn_cmd("navigator", _navigator_task = task_spawn_cmd("navigator",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
2048, 2000,
(main_t)&Navigator::task_main_trampoline, (main_t)&Navigator::task_main_trampoline,
nullptr); nullptr);

View File

@ -1,7 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Julian Oes <joes@student.ethz.ch>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -34,6 +33,8 @@
/** /**
* @file navigator_mission.cpp * @file navigator_mission.cpp
* Helper class to access missions * Helper class to access missions
*
* @author Julian Oes <joes@student.ethz.ch>
*/ */
#include <string.h> #include <string.h>

View File

@ -1,7 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Julian Oes <joes@student.ethz.ch>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions
@ -34,6 +33,8 @@
/** /**
* @file navigator_mission.h * @file navigator_mission.h
* Helper class to access missions * Helper class to access missions
*
* @author Julian Oes <joes@student.ethz.ch>
*/ */
#ifndef NAVIGATOR_MISSION_H #ifndef NAVIGATOR_MISSION_H

View File

@ -1,9 +1,6 @@
/**************************************************************************** /****************************************************************************
* *
* Copyright (c) 2013 PX4 Development Team. All rights reserved. * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
* @author Julian Oes <joes@student.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
* *
* Redistribution and use in source and binary forms, with or without * Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions * modification, are permitted provided that the following conditions

View File

@ -1,8 +1,42 @@
/* /****************************************************************************
* navigator_state.h
* *
* Created on: 27.01.2014 * Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: ton *
* 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 navigator_state.h
*
* Navigator state
*
* @author Anton Babushkin <anton.babushkin@me.com>
*/ */
#ifndef NAVIGATOR_STATE_H_ #ifndef NAVIGATOR_STATE_H_

View File

@ -41,3 +41,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
SRCS = sdlog2.c \ SRCS = sdlog2.c \
logbuffer.c logbuffer.c
MODULE_STACKSIZE = 1200

View File

@ -40,3 +40,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5"
SRCS = sensors.cpp \ SRCS = sensors.cpp \
sensor_params.c sensor_params.c
MODULE_STACKSIZE = 1200

View File

@ -1669,7 +1669,7 @@ Sensors::start()
_sensors_task = task_spawn_cmd("sensors_task", _sensors_task = task_spawn_cmd("sensors_task",
SCHED_DEFAULT, SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5, SCHED_PRIORITY_MAX - 5,
2048, 2000,
(main_t)&Sensors::task_main_trampoline, (main_t)&Sensors::task_main_trampoline,
nullptr); nullptr);

View File

@ -53,7 +53,7 @@
#define SIGMA 0.000001f #define SIGMA 0.000001f
__EXPORT void pid_init(PID_t *pid, uint8_t mode, float dt_min) __EXPORT void pid_init(PID_t *pid, pid_mode_t mode, float dt_min)
{ {
pid->mode = mode; pid->mode = mode;
pid->dt_min = dt_min; pid->dt_min = dt_min;

View File

@ -142,12 +142,9 @@ struct at24c_dev_s {
uint16_t pagesize; /* 32, 63 */ uint16_t pagesize; /* 32, 63 */
uint16_t npages; /* 128, 256, 512, 1024 */ uint16_t npages; /* 128, 256, 512, 1024 */
perf_counter_t perf_reads; perf_counter_t perf_transfers;
perf_counter_t perf_writes; perf_counter_t perf_resets_retries;
perf_counter_t perf_resets; perf_counter_t perf_errors;
perf_counter_t perf_read_retries;
perf_counter_t perf_read_errors;
perf_counter_t perf_write_errors;
}; };
/************************************************************************************ /************************************************************************************
@ -298,9 +295,9 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
for (;;) { for (;;) {
perf_begin(priv->perf_reads); perf_begin(priv->perf_transfers);
ret = I2C_TRANSFER(priv->dev, &msgv[0], 2); ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
perf_end(priv->perf_reads); perf_end(priv->perf_transfers);
if (ret >= 0) if (ret >= 0)
break; break;
@ -314,10 +311,10 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
* XXX maybe do special first-read handling with optional * XXX maybe do special first-read handling with optional
* bus reset as well? * bus reset as well?
*/ */
perf_count(priv->perf_read_retries); perf_count(priv->perf_resets_retries);
if (--tries == 0) { if (--tries == 0) {
perf_count(priv->perf_read_errors); perf_count(priv->perf_errors);
return ERROR; return ERROR;
} }
} }
@ -383,9 +380,9 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
for (;;) { for (;;) {
perf_begin(priv->perf_writes); perf_begin(priv->perf_transfers);
ret = I2C_TRANSFER(priv->dev, &msgv[0], 1); ret = I2C_TRANSFER(priv->dev, &msgv[0], 1);
perf_end(priv->perf_writes); perf_end(priv->perf_transfers);
if (ret >= 0) if (ret >= 0)
break; break;
@ -397,7 +394,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
* poll for write completion. * poll for write completion.
*/ */
if (--tries == 0) { if (--tries == 0) {
perf_count(priv->perf_write_errors); perf_count(priv->perf_errors);
return ERROR; return ERROR;
} }
} }
@ -521,12 +518,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) {
priv->mtd.ioctl = at24c_ioctl; priv->mtd.ioctl = at24c_ioctl;
priv->dev = dev; priv->dev = dev;
priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read"); priv->perf_transfers = perf_alloc(PC_ELAPSED, "eeprom_trans");
priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write"); priv->perf_resets_retries = perf_alloc(PC_COUNT, "eeprom_rst");
priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset"); priv->perf_errors = perf_alloc(PC_COUNT, "eeprom_errs");
priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries");
priv->perf_read_errors = perf_alloc(PC_COUNT, "EEPROM read errors");
priv->perf_write_errors = perf_alloc(PC_COUNT, "EEPROM write errors");
} }
/* attempt to read to validate device is present */ /* attempt to read to validate device is present */
@ -548,9 +542,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) {
} }
}; };
perf_begin(priv->perf_reads); perf_begin(priv->perf_transfers);
int ret = I2C_TRANSFER(priv->dev, &msgv[0], 2); int ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
perf_end(priv->perf_reads); perf_end(priv->perf_transfers);
if (ret < 0) { if (ret < 0) {
return NULL; return NULL;

View File

@ -38,4 +38,4 @@
MODULE_COMMAND = nshterm MODULE_COMMAND = nshterm
SRCS = nshterm.c SRCS = nshterm.c
MODULE_STACKSIZE = 3000 MODULE_STACKSIZE = 1500

View File

@ -38,7 +38,8 @@
MODULE_COMMAND = param MODULE_COMMAND = param
SRCS = param.c SRCS = param.c
MODULE_STACKSIZE = 4096 # Note: measurements yielded a max of 900 bytes used.
MODULE_STACKSIZE = 1800
MAXOPTIMIZATION = -Os MAXOPTIMIZATION = -Os

View File

@ -61,7 +61,7 @@ static void do_load(const char* param_file_name);
static void do_import(const char* param_file_name); static void do_import(const char* param_file_name);
static void do_show(const char* search_string); static void do_show(const char* search_string);
static void do_show_print(void *arg, param_t param); static void do_show_print(void *arg, param_t param);
static void do_set(const char* name, const char* val); static void do_set(const char* name, const char* val, bool fail_on_not_found);
static void do_compare(const char* name, const char* vals[], unsigned comparisons); static void do_compare(const char* name, const char* vals[], unsigned comparisons);
static void do_reset(); static void do_reset();
@ -117,10 +117,17 @@ param_main(int argc, char *argv[])
} }
if (!strcmp(argv[1], "set")) { if (!strcmp(argv[1], "set")) {
if (argc >= 4) { if (argc >= 5) {
do_set(argv[2], argv[3]);
/* if the fail switch is provided, fails the command if not found */
bool fail = !strcmp(argv[4], "fail");
do_set(argv[2], argv[3], fail);
} else if (argc >= 4) {
do_set(argv[2], argv[3], false);
} else { } else {
errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3'"); errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3 [fail]'");
} }
} }
@ -282,7 +289,7 @@ do_show_print(void *arg, param_t param)
} }
static void static void
do_set(const char* name, const char* val) do_set(const char* name, const char* val, bool fail_on_not_found)
{ {
int32_t i; int32_t i;
float f; float f;
@ -290,8 +297,8 @@ do_set(const char* name, const char* val)
/* set nothing if parameter cannot be found */ /* set nothing if parameter cannot be found */
if (param == PARAM_INVALID) { if (param == PARAM_INVALID) {
/* param not found */ /* param not found - fail silenty in scripts as it prevents booting */
errx(1, "Error: Parameter %s not found.", name); errx(((fail_on_not_found) ? 1 : 0), "Error: Parameter %s not found.", name);
} }
printf("%c %s: ", printf("%c %s: ",

View File

@ -39,3 +39,5 @@ MODULE_COMMAND = perf
SRCS = perf.c SRCS = perf.c
MAXOPTIMIZATION = -Os MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1800

View File

@ -40,3 +40,5 @@ MODULE_COMMAND = preflight_check
SRCS = preflight_check.c SRCS = preflight_check.c
MAXOPTIMIZATION = -Os MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1800

View File

@ -38,4 +38,4 @@
MODULE_COMMAND = pwm MODULE_COMMAND = pwm
SRCS = pwm.c SRCS = pwm.c
MODULE_STACKSIZE = 4096 MODULE_STACKSIZE = 1800

View File

@ -39,3 +39,5 @@ MODULE_COMMAND = reboot
SRCS = reboot.c SRCS = reboot.c
MAXOPTIMIZATION = -Os MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 800

View File

@ -38,7 +38,7 @@
MODULE_COMMAND = top MODULE_COMMAND = top
SRCS = top.c SRCS = top.c
MODULE_STACKSIZE = 3000 MODULE_STACKSIZE = 1700
MAXOPTIMIZATION = -Os MAXOPTIMIZATION = -Os