forked from Archive/PX4-Autopilot
merged master, updated fixed wing
This commit is contained in:
commit
57f8fe3719
|
@ -24,4 +24,7 @@ Firmware.sublime-workspace
|
|||
Images/*.bin
|
||||
Images/*.px4
|
||||
mavlink/include/mavlink/v0.9/
|
||||
NuttX
|
||||
/NuttX
|
||||
/Documentation/doxy.log
|
||||
/Documentation/html/
|
||||
/Documentation/doxygen*objdb*tmp
|
|
@ -429,19 +429,19 @@ SORT_BY_SCOPE_NAME = NO
|
|||
# disable (NO) the todo list. This list is created by putting \todo
|
||||
# commands in the documentation.
|
||||
|
||||
GENERATE_TODOLIST = YES
|
||||
GENERATE_TODOLIST = NO
|
||||
|
||||
# The GENERATE_TESTLIST tag can be used to enable (YES) or
|
||||
# disable (NO) the test list. This list is created by putting \test
|
||||
# commands in the documentation.
|
||||
|
||||
GENERATE_TESTLIST = YES
|
||||
GENERATE_TESTLIST = NO
|
||||
|
||||
# The GENERATE_BUGLIST tag can be used to enable (YES) or
|
||||
# disable (NO) the bug list. This list is created by putting \bug
|
||||
# commands in the documentation.
|
||||
|
||||
GENERATE_BUGLIST = YES
|
||||
GENERATE_BUGLIST = NO
|
||||
|
||||
# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or
|
||||
# disable (NO) the deprecated list. This list is created by putting
|
||||
|
@ -569,7 +569,7 @@ WARN_LOGFILE = doxy.log
|
|||
# directories like "/usr/src/myproject". Separate the files or directories
|
||||
# with spaces.
|
||||
|
||||
INPUT = ../apps
|
||||
INPUT = ../src
|
||||
|
||||
# This tag can be used to specify the character encoding of the source files
|
||||
# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is
|
||||
|
@ -599,9 +599,8 @@ RECURSIVE = YES
|
|||
# excluded from the INPUT source files. This way you can easily exclude a
|
||||
# subdirectory from a directory tree whose root is specified with the INPUT tag.
|
||||
|
||||
EXCLUDE = ../dist/ \
|
||||
../docs/html/ \
|
||||
html
|
||||
EXCLUDE = ../src/modules/mathlib/CMSIS \
|
||||
../src/modules/attitude_estimator_ekf/codegen
|
||||
|
||||
# The EXCLUDE_SYMLINKS tag can be used select whether or not files or
|
||||
# directories that are symbolic links (a Unix filesystem feature) are excluded
|
||||
|
|
|
@ -53,6 +53,7 @@
|
|||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_global_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
|
@ -116,6 +117,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
memset(&global_pos, 0, sizeof(global_pos));
|
||||
struct manual_control_setpoint_s manual_sp;
|
||||
memset(&manual_sp, 0, sizeof(manual_sp));
|
||||
struct vehicle_control_mode_s control_mode;
|
||||
memset(&control_mode, 0, sizeof(control_mode));
|
||||
struct vehicle_status_s vstatus;
|
||||
memset(&vstatus, 0, sizeof(vstatus));
|
||||
|
||||
|
@ -137,7 +140,8 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
|
||||
int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
|
||||
int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
|
||||
/* Setup of loop */
|
||||
float gyro[3] = {0.0f, 0.0f, 0.0f};
|
||||
|
@ -178,30 +182,16 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp);
|
||||
orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus);
|
||||
orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
|
||||
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
|
||||
|
||||
gyro[0] = att.rollspeed;
|
||||
gyro[1] = att.pitchspeed;
|
||||
gyro[2] = att.yawspeed;
|
||||
|
||||
/* control */
|
||||
|
||||
if (vstatus.state_machine == SYSTEM_STATE_AUTO ||
|
||||
vstatus.state_machine == SYSTEM_STATE_STABILIZED) {
|
||||
/* attitude control */
|
||||
fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
|
||||
|
||||
/* angular rate control */
|
||||
fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
|
||||
|
||||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
/* set flaps to zero */
|
||||
actuators.control[4] = 0.0f;
|
||||
|
||||
} else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
|
||||
if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
|
||||
/* set manual setpoints if required */
|
||||
if (control_mode.flag_control_manual_enabled) {
|
||||
if (control_mode.flag_control_attitude_enabled) {
|
||||
|
||||
/* if the RC signal is lost, try to stay level and go slowly back down to ground */
|
||||
if (vstatus.rc_signal_lost) {
|
||||
|
@ -234,15 +224,6 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* attitude control */
|
||||
fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
|
||||
|
||||
/* angular rate control */
|
||||
fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
|
||||
|
||||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
/* pass through flaps */
|
||||
if (isfinite(manual_sp.flaps)) {
|
||||
actuators.control[4] = manual_sp.flaps;
|
||||
|
@ -251,7 +232,7 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
actuators.control[4] = 0.0f;
|
||||
}
|
||||
|
||||
} else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
|
||||
} else {
|
||||
/* directly pass through values */
|
||||
actuators.control[0] = manual_sp.roll;
|
||||
/* positive pitch means negative actuator -> pull up */
|
||||
|
@ -267,6 +248,22 @@ int fixedwing_att_control_thread_main(int argc, char *argv[])
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* execute attitude control if requested */
|
||||
if (control_mode.flag_control_attitude_enabled) {
|
||||
/* attitude control */
|
||||
fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
|
||||
|
||||
/* angular rate control */
|
||||
fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
|
||||
|
||||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
/* set flaps to zero */
|
||||
actuators.control[4] = 0.0f;
|
||||
|
||||
}
|
||||
|
||||
/* publish rates */
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
|
||||
|
|
|
@ -37,6 +37,10 @@
|
|||
* Common object definitions without a better home.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @defgroup topics List of all uORB topics.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <drivers/drv_orb_dev.h>
|
||||
|
|
|
@ -55,11 +55,20 @@
|
|||
/* control sets with pre-defined applications */
|
||||
#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct actuator_controls_s {
|
||||
uint64_t timestamp;
|
||||
float control[NUM_ACTUATOR_CONTROLS];
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* actuator control sets; this list can be expanded as more controllers emerge */
|
||||
ORB_DECLARE(actuator_controls_0);
|
||||
ORB_DECLARE(actuator_controls_1);
|
||||
|
|
|
@ -53,11 +53,20 @@
|
|||
#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
|
||||
#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct actuator_controls_effective_s {
|
||||
uint64_t timestamp;
|
||||
float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* actuator control sets; this list can be expanded as more controllers emerge */
|
||||
ORB_DECLARE(actuator_controls_effective_0);
|
||||
ORB_DECLARE(actuator_controls_effective_1);
|
||||
|
|
|
@ -52,12 +52,21 @@
|
|||
#define NUM_ACTUATOR_OUTPUTS 16
|
||||
#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct actuator_outputs_s {
|
||||
uint64_t timestamp; /**< output timestamp in us since system boot */
|
||||
float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */
|
||||
int noutputs; /**< valid outputs */
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* actuator output sets; this list can be expanded as more drivers emerge */
|
||||
ORB_DECLARE(actuator_outputs_0);
|
||||
ORB_DECLARE(actuator_outputs_1);
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
|
|
|
@ -51,10 +51,6 @@
|
|||
#include <stdbool.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* The number of ESCs supported.
|
||||
* Current (Q2/2013) we support 8 ESCs,
|
||||
|
@ -76,7 +72,12 @@ enum ESC_CONNECTION_TYPE {
|
|||
};
|
||||
|
||||
/**
|
||||
*
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* Electronic speed controller status.
|
||||
*/
|
||||
struct esc_status_s
|
||||
{
|
||||
|
|
|
@ -46,11 +46,6 @@
|
|||
#include <stdbool.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
enum NAV_CMD {
|
||||
NAV_CMD_WAYPOINT = 0,
|
||||
NAV_CMD_LOITER_TURN_COUNT,
|
||||
|
@ -61,6 +56,11 @@ enum NAV_CMD {
|
|||
NAV_CMD_TAKEOFF
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* Global position setpoint in WGS84 coordinates.
|
||||
*
|
||||
|
|
|
@ -43,11 +43,6 @@
|
|||
#include <stdint.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* Off-board control inputs.
|
||||
*
|
||||
|
@ -66,6 +61,11 @@ enum OFFBOARD_CONTROL_MODE
|
|||
OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct offboard_control_setpoint_s {
|
||||
uint64_t timestamp;
|
||||
|
||||
|
|
|
@ -46,6 +46,7 @@
|
|||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
|
|
|
@ -42,11 +42,20 @@
|
|||
#include <stdint.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct parameter_update_s {
|
||||
/** time at which the latest parameter was updated */
|
||||
uint64_t timestamp;
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
ORB_DECLARE(parameter_update);
|
||||
|
||||
#endif
|
|
@ -45,11 +45,6 @@
|
|||
#include <stdint.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* The number of RC channel inputs supported.
|
||||
* Current (Q1/2013) radios support up to 18 channels,
|
||||
|
@ -85,6 +80,11 @@ enum RC_CHANNELS_FUNCTION
|
|||
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct rc_channels_s {
|
||||
|
||||
uint64_t timestamp; /**< In microseconds since boot time. */
|
||||
|
|
|
@ -46,17 +46,17 @@
|
|||
#include <stdbool.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
enum MAGNETOMETER_MODE {
|
||||
MAGNETOMETER_MODE_NORMAL = 0,
|
||||
MAGNETOMETER_MODE_POSITIVE_BIAS,
|
||||
MAGNETOMETER_MODE_NEGATIVE_BIAS
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* Sensor readings in raw and SI-unit form.
|
||||
*
|
||||
|
|
|
@ -50,10 +50,6 @@
|
|||
#include <stdbool.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
*/
|
||||
|
||||
enum SUBSYSTEM_TYPE
|
||||
{
|
||||
SUBSYSTEM_TYPE_GYRO = 1,
|
||||
|
@ -75,6 +71,10 @@ enum SUBSYSTEM_TYPE
|
|||
SUBSYSTEM_TYPE_RANGEFINDER = 131072
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
*/
|
||||
|
||||
/**
|
||||
* State of individual sub systems
|
||||
*/
|
||||
|
|
|
@ -50,6 +50,11 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
|
|||
TELEMETRY_STATUS_RADIO_TYPE_WIRE
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct telemetry_status_s {
|
||||
uint64_t timestamp;
|
||||
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
|
||||
|
@ -62,6 +67,10 @@ struct telemetry_status_s {
|
|||
uint8_t txbuf; /**< how full the tx buffer is as a percentage */
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
ORB_DECLARE(telemetry_status);
|
||||
|
||||
#endif /* TOPIC_TELEMETRY_STATUS_H */
|
|
@ -48,6 +48,7 @@
|
|||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
|
|
|
@ -45,11 +45,6 @@
|
|||
#include <stdint.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* Commands for commander app.
|
||||
*
|
||||
|
@ -110,6 +105,10 @@ enum VEHICLE_CMD_RESULT
|
|||
VEHICLE_CMD_RESULT_ENUM_END=5, /* | */
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct vehicle_command_s
|
||||
{
|
||||
|
|
|
@ -60,8 +60,8 @@
|
|||
*/
|
||||
struct vehicle_global_position_set_triplet_s
|
||||
{
|
||||
bool previous_valid;
|
||||
bool next_valid;
|
||||
bool previous_valid; /**< flag indicating previous position is valid */
|
||||
bool next_valid; /**< flag indicating next position is valid */
|
||||
|
||||
struct vehicle_global_position_setpoint_s previous;
|
||||
struct vehicle_global_position_setpoint_s current;
|
||||
|
|
|
@ -159,6 +159,10 @@ enum VEHICLE_BATTERY_WARNING {
|
|||
VEHICLE_BATTERY_WARNING_ALERT /**< alerting of low voltage 2. stage */
|
||||
};
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* state machine / state of vehicle.
|
||||
|
|
Loading…
Reference in New Issue