Conflicts:
	libraries/APM_PI/APM_PI.cpp
This commit is contained in:
Jason Short 2011-10-27 12:41:00 -07:00
commit 27d9712e80
268 changed files with 51441 additions and 4431 deletions

View File

@ -22,3 +22,4 @@
#include "APO_DefaultSetup.h"
#include <WProgram.h>; int main(void) {init();setup();for(;;) loop(); return 0; }
// vim:ts=4:sw=4:expandtab

View File

@ -20,3 +20,4 @@
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"
// vim:ts=4:sw=4:expandtab

View File

@ -3,6 +3,7 @@
*
* Created on: May 1, 2011
* Author: jgoppert
*
*/
#ifndef BOATGENERIC_H_
@ -27,10 +28,10 @@ static const uint8_t heartBeatTimeout = 3;
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
// baud rates
static uint32_t debugBaud = 57600;
static uint32_t telemBaud = 57600;
static uint32_t gpsBaud = 38400;
static uint32_t hilBaud = 57600;
static const uint32_t debugBaud = 57600;
static const uint32_t telemBaud = 57600;
static const uint32_t gpsBaud = 38400;
static const uint32_t hilBaud = 57600;
// optional sensors
static const bool gpsEnabled = false;
@ -61,20 +62,26 @@ static const float loop2Rate = 1; // gcs slow
static const float loop3Rate = 0.1;
// gains
const float steeringP = 1.0;
const float steeringI = 0.0;
const float steeringD = 0.0;
const float steeringIMax = 0.0;
const float steeringYMax = 3.0;
const float steeringDFCut = 25;
static const float steeringP = 0.1;
static const float steeringI = 0.0;
static const float steeringD = 0.1;
static const float steeringIMax = 0.0;
static const float steeringYMax = 1;
static const float steeringDFCut = 25.0;
const float throttleP = 0.0;
const float throttleI = 0.0;
const float throttleD = 0.0;
const float throttleIMax = 0.0;
const float throttleYMax = 0.0;
const float throttleDFCut = 3.0;
static const float throttleP = 0.1;
static const float throttleI = 0.0;
static const float throttleD = 0.0;
static const float throttleIMax = 0.0;
static const float throttleYMax = 1;
static const float throttleDFCut = 0.0;
// guidance
static const float velCmd = 5;
static const float xt = 10;
static const float xtLim = 90;
#include "ControllerBoat.h"
#endif /* BOATGENERIC_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -13,113 +13,68 @@
namespace apo {
class ControllerBoat: public AP_Controller {
private:
AP_Var_group _group;
AP_Uint8 _mode;
enum {
k_chMode = k_radioChannelsStart, k_chStr, k_chThr
};
enum {
k_pidStr = k_controllersStart, k_pidThr
};
enum {
CH_MODE = 0, CH_STR, CH_THR
};
BlockPIDDfb pidStr;
BlockPID pidThr;
public:
ControllerBoat(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
_group(k_cntrl, PSTR("CNTRL_")),
_mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax, steeringDFCut),
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut) {
_hal->debug->println_P(PSTR("initializing boat controller"));
ControllerBoat(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal,new AP_ArmingMechanism(hal,ch_thrust,ch_str,0.1,-0.9,0.9), ch_mode),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax,steeringDFCut),
pidThrust(new AP_Var_group(k_pidThrust, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut), _strCmd(0), _thrustCmd(0)
{
_hal->debug->println_P(PSTR("initializing boat controller"));
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 7, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540,
1900, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_INOUT, false));
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
virtual void update(const float & dt) {
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 3, 1100, 1500,
1900, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThrust, PSTR("THR_"), APM_RC, 2, 1100, 1500,
1900, RC_MODE_INOUT, false));
}
// check for heartbeat
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n"));
return;
// if throttle less than 5% cut motor power
} else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) {
_mode = MAV_MODE_LOCKED;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_STANDBY);
return;
// if in live mode then set state to active
} else if (_hal->getMode() == MODE_LIVE) {
_hal->setState(MAV_STATE_ACTIVE);
// if in hardware in the loop (control) mode, set to hilsim
} else if (_hal->getMode() == MODE_HIL_CNTL) {
_hal->setState(MAV_STATE_HILSIM);
}
private:
// methdos
void manualLoop(const float dt) {
setAllRadioChannelsManually();
_strCmd = _hal->rc[ch_str]->getRadioPosition();
_thrustCmd = _hal->rc[ch_thrust]->getRadioPosition();
}
void autoLoop(const float dt) {
_strCmd = pidStr.update(_guide->getHeadingError(), _nav->getYawRate(), dt);
_thrustCmd = pidThrust.update(
_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt);
}
void setMotorsActive() {
// turn all motors off if below 0.1 throttle
if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) {
setAllRadioChannelsToNeutral();
} else {
_hal->rc[ch_thrust]->setPosition(_thrustCmd);
_hal->rc[ch_str]->setPosition(_strCmd);
}
}
// read switch to set mode
if (_hal->rc[CH_MODE]->getRadioPosition() > 0) {
_mode = MAV_MODE_MANUAL;
} else {
_mode = MAV_MODE_AUTO;
}
// manual mode
switch (_mode) {
case MAV_MODE_MANUAL: {
setAllRadioChannelsManually();
//_hal->debug->println("manual");
break;
}
case MAV_MODE_AUTO: {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
_hal->rc[CH_STR]->setPosition(
pidStr.update(headingError, _nav->getYawRate(), dt));
_hal->rc[CH_THR]->setPosition(
pidThr.update(
_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt));
//_hal->debug->println("automode");
break;
}
default: {
setAllRadioChannelsToNeutral();
_mode = MAV_MODE_FAILSAFE;
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("unknown controller mode\n"));
break;
}
}
}
// attributes
enum {
ch_mode = 0, ch_str, ch_thrust
};
enum {
k_chMode = k_radioChannelsStart, k_chStr, k_chThrust
};
enum {
k_pidStr = k_controllersStart, k_pidThrust
};
BlockPIDDfb pidStr;
BlockPID pidThrust;
float _strCmd, _thrustCmd;
};
} // namespace apo
#endif /* CONTROLLERBOAT_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -27,7 +27,6 @@
V_FRAME
*/
# define CH7_OPTION CH7_DO_NOTHING
/*
CH7_DO_NOTHING
@ -52,8 +51,7 @@
//#define RATE_ROLL_I 0.18
//#define RATE_PITCH_I 0.18
//#define MOTORS_JD880
// agmatthews USERHOOKS

View File

@ -135,10 +135,14 @@ private:
uint16_t _parameter_count; ///< cache of reportable parameters
AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index
mavlink_channel_t chan;
uint16_t packet_drops;
#if CLI_ENABLED == ENABLED
// this allows us to detect the user wanting the CLI to start
uint8_t crlf_count;
#endif
// waypoints
uint16_t waypoint_request_i; // request index
uint16_t waypoint_dest_sysid; // where to send requests
@ -150,7 +154,6 @@ private:
uint32_t waypoint_timelast_receive; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds
float junk; //used to return a junk value for interface
// data stream rates
AP_Var_group _group;

View File

@ -8,6 +8,9 @@ static bool in_mavlink_delay;
// messages don't block the CPU
static mavlink_statustext_t pending_status;
// true when we have received at least 1 MAVLink packet
static bool mavlink_active;
// check if a message will fit in the payload space available
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
@ -539,8 +542,26 @@ GCS_MAVLINK::update(void)
{
uint8_t c = comm_receive_ch(chan);
#if CLI_ENABLED == ENABLED
/* allow CLI to be started by hitting enter 3 times, if no
heartbeat packets have been received */
if (mavlink_active == false) {
if (c == '\n' || c == '\r') {
crlf_count++;
} else {
crlf_count = 0;
}
if (crlf_count == 3) {
run_cli();
}
}
#endif
// Try to get a new message
if(mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg);
if (mavlink_parse_char(chan, c, &msg, &status)) {
mavlink_active = true;
handleMessage(&msg);
}
}
// Update packet drops counter

View File

@ -361,6 +361,19 @@
//////////////////////////////////////////////////////////////////////////////
// Attitude Control
//
// Extra motor values that are changed from time to time by jani @ jDrones as software
// and charachteristics changes.
#ifdef MOTORS_JD880
# define STABILIZE_ROLL_P 3.6
# define STABILIZE_ROLL_I 0.06
# define STABILIZE_ROLL_IMAX 2.0 // degrees
# define STABILIZE_PITCH_P 3.6
# define STABILIZE_PITCH_I 0.06
# define STABILIZE_PITCH_IMAX 2.0 // degrees
#endif
// Jasons default values that are good for smaller payload motors.
#ifndef STABILIZE_ROLL_P
# define STABILIZE_ROLL_P 4.6
#endif
@ -702,6 +715,11 @@
# define CLI_ENABLED ENABLED
#endif
// use this to disable the CLI slider switch
#ifndef CLI_SLIDER_ENABLED
# define CLI_SLIDER_ENABLED ENABLED
#endif
// delay to prevent Xbee bricking, in milliseconds
#ifndef MAVLINK_TELEMETRY_PORT_DELAY
# define MAVLINK_TELEMETRY_PORT_DELAY 2000

View File

@ -43,6 +43,14 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
// Create the top-level menu object.
MENU(main_menu, THISFIRMWARE, main_menu_commands);
// the user wants the CLI. It never exits
static void run_cli(void)
{
while (1) {
main_menu.run();
}
}
#endif // CLI_ENABLED
static void init_ardupilot()
@ -215,7 +223,7 @@ static void init_ardupilot()
DataFlash.Init();
#endif
#if CLI_ENABLED == ENABLED
#if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
// If the switch is in 'menu' mode, run the main menu.
//
// Since we can't be sure that the setup or test mode won't leave
@ -225,11 +233,10 @@ static void init_ardupilot()
if (check_startup_for_CLI()) {
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
Serial.printf_P(PSTR("\nCLI:\n\n"));
for (;;) {
//Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
main_menu.run();
}
run_cli();
}
#else
Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n"));
#endif // CLI_ENABLED
if(g.esc_calibrate == 1){

View File

@ -135,10 +135,14 @@ private:
uint16_t _parameter_count; ///< cache of reportable parameters
AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index
mavlink_channel_t chan;
uint16_t packet_drops;
#if CLI_ENABLED == ENABLED
// this allows us to detect the user wanting the CLI to start
uint8_t crlf_count;
#endif
// waypoints
uint16_t waypoint_request_i; // request index
uint16_t waypoint_dest_sysid; // where to send requests
@ -150,7 +154,6 @@ private:
uint32_t waypoint_timelast_receive; // milliseconds
uint16_t waypoint_send_timeout; // milliseconds
uint16_t waypoint_receive_timeout; // milliseconds
float junk; //used to return a junk value for interface
// data stream rates
AP_Var_group _group;

View File

@ -1,5 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Mavlink_compat.h"
// use this to prevent recursion during sensor init
static bool in_mavlink_delay;
@ -7,6 +9,8 @@ static bool in_mavlink_delay;
// messages don't block the CPU
static mavlink_statustext_t pending_status;
// true when we have received at least 1 MAVLink packet
static bool mavlink_active;
// check if a message will fit in the payload space available
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
@ -23,10 +27,85 @@ static mavlink_statustext_t pending_status;
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{
#ifdef MAVLINK10
uint8_t base_mode = 0;
uint8_t system_status = MAV_STATE_ACTIVE;
// we map the custom_mode to our internal mode plus 16, to lower
// the chance that a ground station will give us 0 and we
// interpret it as manual. This is necessary as the SET_MODE
// command has no way to indicate that the custom_mode is filled in
uint32_t custom_mode = control_mode + 16;
// work out the base_mode. This value is almost completely useless
// for APM, but we calculate it as best we can so a generic
// MAVLink enabled ground station can work out something about
// what the MAV is up to. The actual bit values are highly
// ambiguous for most of the APM flight modes. In practice, you
// only get useful information from the custom_mode, which maps to
// the APM flight mode and has a well defined meaning in the
// ArduPlane documentation
switch (control_mode) {
case MANUAL:
base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
break;
case STABILIZE:
case FLY_BY_WIRE_A:
case FLY_BY_WIRE_B:
case FLY_BY_WIRE_C:
base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
break;
case AUTO:
case RTL:
case LOITER:
case GUIDED:
case CIRCLE:
base_mode = MAV_MODE_FLAG_GUIDED_ENABLED |
MAV_MODE_FLAG_STABILIZE_ENABLED;
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
// APM does in any mode, as that is defined as "system finds its own goal
// positions", which APM does not currently do
break;
case INITIALISING:
system_status = MAV_STATE_CALIBRATING;
break;
}
if (control_mode != MANUAL && control_mode != INITIALISING) {
// stabiliser of some form is enabled
base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
}
#if ENABLE_STICK_MIXING==ENABLED
if (control_mode != INITIALISING) {
// all modes except INITIALISING have some form of manual
// override if stick mixing is enabled
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
#endif
#if HIL_MODE != HIL_MODE_DISABLED
base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
#endif
// we are armed if we are not initialising
if (control_mode != INITIALISING) {
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
mavlink_msg_heartbeat_send(
chan,
MAV_TYPE_FIXED_WING,
MAV_AUTOPILOT_ARDUPILOTMEGA,
base_mode,
custom_mode,
system_status);
#else // MAVLINK10
mavlink_msg_heartbeat_send(
chan,
mavlink_system.type,
MAV_AUTOPILOT_ARDUPILOTMEGA);
#endif // MAVLINK10
}
static NOINLINE void send_attitude(mavlink_channel_t chan)
@ -45,6 +124,103 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops)
{
#ifdef MAVLINK10
uint32_t control_sensors_present = 0;
uint32_t control_sensors_enabled;
uint32_t control_sensors_health;
// first what sensors/controllers we have
control_sensors_present |= (1<<0); // 3D gyro present
control_sensors_present |= (1<<1); // 3D accelerometer present
if (g.compass_enabled) {
control_sensors_present |= (1<<2); // compass present
}
control_sensors_present |= (1<<3); // absolute pressure sensor present
if (g_gps->fix) {
control_sensors_present |= (1<<5); // GPS present
}
control_sensors_present |= (1<<10); // 3D angular rate control
control_sensors_present |= (1<<11); // attitude stabilisation
control_sensors_present |= (1<<12); // yaw position
control_sensors_present |= (1<<13); // altitude control
control_sensors_present |= (1<<14); // X/Y position control
control_sensors_present |= (1<<15); // motor control
// now what sensors/controllers are enabled
// first the sensors
control_sensors_enabled = control_sensors_present & 0x1FF;
// now the controllers
control_sensors_enabled = control_sensors_present & 0x1FF;
switch (control_mode) {
case MANUAL:
break;
case STABILIZE:
case FLY_BY_WIRE_A:
control_sensors_enabled |= (1<<10); // 3D angular rate control
control_sensors_enabled |= (1<<11); // attitude stabilisation
break;
case FLY_BY_WIRE_B:
control_sensors_enabled |= (1<<10); // 3D angular rate control
control_sensors_enabled |= (1<<11); // attitude stabilisation
control_sensors_enabled |= (1<<15); // motor control
break;
case FLY_BY_WIRE_C:
control_sensors_enabled |= (1<<10); // 3D angular rate control
control_sensors_enabled |= (1<<11); // attitude stabilisation
control_sensors_enabled |= (1<<13); // altitude control
control_sensors_enabled |= (1<<15); // motor control
break;
case AUTO:
case RTL:
case LOITER:
case GUIDED:
case CIRCLE:
control_sensors_enabled |= (1<<10); // 3D angular rate control
control_sensors_enabled |= (1<<11); // attitude stabilisation
control_sensors_enabled |= (1<<12); // yaw position
control_sensors_enabled |= (1<<13); // altitude control
control_sensors_enabled |= (1<<14); // X/Y position control
control_sensors_enabled |= (1<<15); // motor control
break;
case INITIALISING:
break;
}
// at the moment all sensors/controllers are assumed healthy
control_sensors_health = control_sensors_present;
uint16_t battery_current = -1;
uint8_t battery_remaining = -1;
if (current_total != 0 && g.pack_capacity != 0) {
battery_remaining = (100.0 * (g.pack_capacity - current_total) / g.pack_capacity);
}
if (current_total != 0) {
battery_current = current_amps * 100;
}
mavlink_msg_sys_status_send(
chan,
control_sensors_present,
control_sensors_enabled,
control_sensors_health,
(uint16_t)(load * 1000),
battery_voltage * 1000, // mV
battery_current, // in 10mA units
battery_remaining, // in %
0, // comm drops %,
0, // comm drops in pkts,
0, 0, 0, 0);
#else // MAVLINK10
uint8_t mode = MAV_MODE_UNINIT;
uint8_t nav_mode = MAV_NAV_VECTOR;
@ -96,6 +272,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
battery_voltage * 1000,
battery_remaining,
packet_drops);
#endif // MAVLINK10
}
static void NOINLINE send_meminfo(mavlink_channel_t chan)
@ -107,6 +284,19 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan)
static void NOINLINE send_location(mavlink_channel_t chan)
{
Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now
#ifdef MAVLINK10
mavlink_msg_global_position_int_send(
chan,
millis(),
current_loc.lat, // in 1E7 degrees
current_loc.lng, // in 1E7 degrees
g_gps->altitude*10, // millimeters above sea level
current_loc.alt * 10, // millimeters above ground
g_gps->ground_speed * rot.a.x, // X speed cm/s
g_gps->ground_speed * rot.b.x, // Y speed cm/s
g_gps->ground_speed * rot.c.x,
g_gps->ground_course); // course in 1/100 degree
#else // MAVLINK10
mavlink_msg_global_position_int_send(
chan,
current_loc.lat,
@ -115,6 +305,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
g_gps->ground_speed * rot.a.x,
g_gps->ground_speed * rot.b.x,
g_gps->ground_speed * rot.c.x);
#endif // MAVLINK10
}
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
@ -133,6 +324,28 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
{
#ifdef MAVLINK10
uint8_t fix;
if (g_gps->status() == 2) {
fix = 3;
} else {
fix = 0;
}
mavlink_msg_gps_raw_int_send(
chan,
micros(),
fix,
g_gps->latitude, // in 1E7 degrees
g_gps->longitude, // in 1E7 degrees
g_gps->altitude * 10, // in mm
g_gps->hdop,
65535,
g_gps->ground_speed, // cm/s
g_gps->ground_course, // 1/100 degrees,
g_gps->num_sats);
#else // MAVLINK10
mavlink_msg_gps_raw_send(
chan,
micros(),
@ -144,13 +357,31 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
0.0,
g_gps->ground_speed / 100.0,
g_gps->ground_course / 100.0);
#endif // MAVLINK10
}
static void NOINLINE send_servo_out(mavlink_channel_t chan)
{
const uint8_t rssi = 1;
// normalized values scaled to -10000 to 10000
// This is used for HIL. Do not change without discussing with HIL maintainers
// This is used for HIL. Do not change without discussing with
// HIL maintainers
#ifdef MAVLINK10
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
10000 * g.channel_roll.norm_output(),
10000 * g.channel_pitch.norm_output(),
10000 * g.channel_throttle.norm_output(),
10000 * g.channel_rudder.norm_output(),
0,
0,
0,
0,
rssi);
#else // MAVLINK10
mavlink_msg_rc_channels_scaled_send(
chan,
10000 * g.channel_roll.norm_output(),
@ -162,12 +393,29 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
0,
0,
rssi);
#endif // MAVLINK10
}
static void NOINLINE send_radio_in(mavlink_channel_t chan)
{
uint8_t rssi = 1;
#ifdef MAVLINK10
mavlink_msg_rc_channels_raw_send(
chan,
millis(),
0, // port
g.channel_roll.radio_in,
g.channel_pitch.radio_in,
g.channel_throttle.radio_in,
g.channel_rudder.radio_in,
g.rc_5.radio_in, // XXX currently only 4 RC channels defined
g.rc_6.radio_in,
g.rc_7.radio_in,
g.rc_8.radio_in,
rssi);
#else // MAVLINK10
mavlink_msg_rc_channels_raw_send(
chan,
g.channel_roll.radio_in,
g.channel_pitch.radio_in,
@ -178,10 +426,25 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan)
g.rc_7.radio_in,
g.rc_8.radio_in,
rssi);
#endif // MAVLINK10
}
static void NOINLINE send_radio_out(mavlink_channel_t chan)
{
#ifdef MAVLINK10
mavlink_msg_servo_output_raw_send(
chan,
micros(),
0, // port
g.channel_roll.radio_out,
g.channel_pitch.radio_out,
g.channel_throttle.radio_out,
g.channel_rudder.radio_out,
g.rc_5.radio_out, // XXX currently only 4 RC channels defined
g.rc_6.radio_out,
g.rc_7.radio_out,
g.rc_8.radio_out);
#else // MAVLINK10
mavlink_msg_servo_output_raw_send(
chan,
g.channel_roll.radio_out,
@ -192,6 +455,7 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
g.rc_6.radio_out,
g.rc_7.radio_out,
g.rc_8.radio_out);
#endif // MAVLINK10
}
static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
@ -325,7 +589,11 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
break;
case MSG_GPS_RAW:
#ifdef MAVLINK10
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
#else
CHECK_PAYLOAD_SIZE(GPS_RAW);
#endif
send_gps_raw(chan);
break;
@ -480,10 +748,11 @@ void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char
mavlink_send_message(chan, MSG_STATUSTEXT, 0);
} else {
// send immediately
mavlink_msg_statustext_send(
chan,
severity,
(const int8_t*) str);
#ifdef MAVLINK10
mavlink_msg_statustext_send(chan, severity, str);
#else
mavlink_msg_statustext_send(chan, severity, (const int8_t*) str);
#endif
}
}
@ -538,8 +807,26 @@ GCS_MAVLINK::update(void)
{
uint8_t c = comm_receive_ch(chan);
#if CLI_ENABLED == ENABLED
/* allow CLI to be started by hitting enter 3 times, if no
heartbeat packets have been received */
if (mavlink_active == 0) {
if (c == '\n' || c == '\r') {
crlf_count++;
} else {
crlf_count = 0;
}
if (crlf_count == 3) {
run_cli();
}
}
#endif
// Try to get a new message
if (mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg);
if (mavlink_parse_char(chan, c, &msg, &status)) {
mavlink_active = 1;
handleMessage(&msg);
}
}
// Update packet drops counter
@ -721,6 +1008,68 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#ifdef MAVLINK10
case MAVLINK_MSG_ID_COMMAND_LONG:
{
// decode
mavlink_command_long_t packet;
mavlink_msg_command_long_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
uint8_t result;
// do command
send_text(SEVERITY_LOW,PSTR("command received: "));
switch(packet.command) {
case MAV_CMD_NAV_LOITER_UNLIM:
set_mode(LOITER);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
set_mode(RTL);
result = MAV_RESULT_ACCEPTED;
break;
#if 0
// not implemented yet, but could implement some of them
case MAV_CMD_NAV_LAND:
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_NAV_ROI:
case MAV_CMD_NAV_PATHPLANNING:
break;
#endif
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
packet.param2 == 1 ||
packet.param3 == 1) {
startup_IMU_ground();
}
if (packet.param4 == 1) {
trim_radio();
}
result = MAV_RESULT_ACCEPTED;
break;
default:
result = MAV_RESULT_UNSUPPORTED;
break;
}
mavlink_msg_command_ack_send(
chan,
packet.command,
result);
break;
}
#else // MAVLINK10
case MAVLINK_MSG_ID_ACTION:
{
// decode
@ -840,6 +1189,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#endif
case MAVLINK_MSG_ID_SET_MODE:
{
@ -847,6 +1197,29 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
#ifdef MAVLINK10
// we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on
// custom_mode instead.
// see comment on custom_mode above
int16_t adjusted_mode = packet.custom_mode - 16;
switch (adjusted_mode) {
case MANUAL:
case CIRCLE:
case STABILIZE:
case FLY_BY_WIRE_A:
case FLY_BY_WIRE_B:
case FLY_BY_WIRE_C:
case AUTO:
case RTL:
case LOITER:
set_mode(adjusted_mode);
break;
}
#else // MAVLINK10
switch(packet.mode){
case MAV_MODE_MANUAL:
@ -876,8 +1249,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#endif
break;
}
#ifndef MAVLINK10
case MAVLINK_MSG_ID_SET_NAV_MODE:
{
// decode
@ -887,6 +1263,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mav_nav = packet.nav_mode;
break;
}
#endif // MAVLINK10
case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST:
{
@ -910,6 +1288,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
// XXX read a WP from EEPROM and send it to the GCS
case MAVLINK_MSG_ID_WAYPOINT_REQUEST:
{
@ -1021,6 +1400,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
case MAVLINK_MSG_ID_WAYPOINT_ACK:
{
// decode
@ -1056,13 +1436,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
// clear all waypoints
const uint8_t type = 0; // ok (0), error(1)
g.waypoint_total.set_and_save(0);
// send acknowledgement 3 times to makes sure it is received
for (uint8_t i=0;i<3;i++)
mavlink_msg_waypoint_ack_send(chan, msg->sysid, msg->compid, type);
// note that we don't send multiple acks, as otherwise a
// GCS that is doing a clear followed by a set may see
// the additional ACKs as ACKs of the set operations
mavlink_msg_waypoint_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ACCEPTED);
break;
}
@ -1116,6 +1495,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
{
// decode
mavlink_waypoint_t packet;
uint8_t result = MAV_MISSION_ACCEPTED;
mavlink_msg_waypoint_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break;
@ -1134,6 +1515,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#ifdef MAV_FRAME_LOCAL_NED
case MAV_FRAME_LOCAL_NED: // local (relative to home position)
{
tell_command.lat = 1.0e7*ToDeg(packet.x/
(radius_of_earth*cos(ToRad(home.lat/1.0e7)))) + home.lat;
tell_command.lng = 1.0e7*ToDeg(packet.y/radius_of_earth) + home.lng;
tell_command.alt = -packet.z*1.0e2;
tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
break;
}
#endif
#ifdef MAV_FRAME_LOCAL
case MAV_FRAME_LOCAL: // local (relative to home position)
{
tell_command.lat = 1.0e7*ToDeg(packet.x/
@ -1143,6 +1537,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
tell_command.options = MASK_OPTIONS_RELATIVE_ALT;
break;
}
#endif
case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude
{
tell_command.lat = 1.0e7 * packet.x; // in as DD converted to * t7
@ -1151,9 +1547,22 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
tell_command.options = MASK_OPTIONS_RELATIVE_ALT; // store altitude relative!! Always!!
break;
}
default:
result = MAV_MISSION_UNSUPPORTED_FRAME;
break;
}
if (result != MAV_MISSION_ACCEPTED) goto mission_failed;
switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_NAV_LOITER_UNLIM:
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
case MAV_CMD_NAV_LAND:
break;
case MAV_CMD_NAV_LOITER_TURNS:
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_DO_SET_HOME:
@ -1193,8 +1602,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
tell_command.alt = packet.param2;
tell_command.p1 = packet.param1;
break;
default:
#ifdef MAVLINK10
result = MAV_MISSION_UNSUPPORTED;
#endif
break;
}
if (result != MAV_MISSION_ACCEPTED) goto mission_failed;
if(packet.current == 2){ //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission
guided_WP = tell_command;
@ -1217,24 +1634,29 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} else {
// Check if receiving waypoints (mission upload expected)
if (!waypoint_receiving) break;
if (!waypoint_receiving) {
result = MAV_MISSION_ERROR;
goto mission_failed;
}
// check if this is the requested waypoint
if (packet.seq != waypoint_request_i) break;
set_wp_with_index(tell_command, packet.seq);
if (packet.seq != waypoint_request_i) {
result = MAV_MISSION_INVALID_SEQUENCE;
goto mission_failed;
}
set_wp_with_index(tell_command, packet.seq);
// update waypoint receiving state machine
waypoint_timelast_receive = millis();
waypoint_request_i++;
if (waypoint_request_i > (uint16_t)g.waypoint_total){
uint8_t type = 0; // ok (0), error(1)
mavlink_msg_waypoint_ack_send(
chan,
msg->sysid,
msg->compid,
type);
result);
send_text(SEVERITY_LOW,PSTR("flight plan received"));
waypoint_receiving = false;
@ -1243,6 +1665,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
}
break;
mission_failed:
// we are rejecting the mission/waypoint
mavlink_msg_waypoint_ack_send(
chan,
msg->sysid,
msg->compid,
result);
break;
}
case MAVLINK_MSG_ID_PARAM_SET:
@ -1280,10 +1711,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// handle variables with standard type IDs
if (var_type == AP_Var::k_typeid_float) {
((AP_Float *)vp)->set_and_save(packet.param_value);
} else if (var_type == AP_Var::k_typeid_float16) {
((AP_Float16 *)vp)->set_and_save(packet.param_value);
} else if (var_type == AP_Var::k_typeid_int32) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition);
@ -1302,12 +1731,22 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// we send the value we actually set, which could be
// different from the value sent, in case someone sent
// a fractional value to an integer type
#ifdef MAVLINK10
mavlink_msg_param_value_send(
chan,
key,
vp->cast_to_float(),
mav_var_type(vp->meta_type_id()),
_count_parameters(),
-1); // XXX we don't actually know what its index is...
#else // MAVLINK10
mavlink_msg_param_value_send(
chan,
(int8_t *)key,
vp->cast_to_float(),
_count_parameters(),
-1); // XXX we don't actually know what its index is...
-1); // XXX we don't actually know what its index is...
#endif // MAVLINK10
}
break;
@ -1351,6 +1790,20 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
#if HIL_MODE != HIL_MODE_DISABLED
// This is used both as a sensor and to pass the location
// in HIL_ATTITUDE mode.
#ifdef MAVLINK10
case MAVLINK_MSG_ID_GPS_RAW_INT:
{
// decode
mavlink_gps_raw_int_t packet;
mavlink_msg_gps_raw_int_decode(msg, &packet);
// set gps hil sensor
g_gps->setHIL(packet.time_usec/1000.0,
packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3,
packet.vel*1.0e-2, packet.cog*1.0e-2, 0, 0);
break;
}
#else // MAVLINK10
case MAVLINK_MSG_ID_GPS_RAW:
{
// decode
@ -1362,6 +1815,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
packet.v,packet.hdg,0,0);
break;
}
#endif // MAVLINK10
// Is this resolved? - MAVLink protocol change.....
case MAVLINK_MSG_ID_VFR_HUD:
@ -1505,12 +1959,22 @@ GCS_MAVLINK::queued_param_send()
char param_name[ONBOARD_PARAM_NAME_LENGTH]; /// XXX HACK
vp->copy_name(param_name, sizeof(param_name));
#ifdef MAVLINK10
mavlink_msg_param_value_send(
chan,
param_name,
value,
mav_var_type(vp->meta_type_id()),
_queued_parameter_count,
_queued_parameter_index);
#else // MAVLINK10
mavlink_msg_param_value_send(
chan,
(int8_t*)param_name,
value,
_queued_parameter_count,
_queued_parameter_index);
#endif // MAVLINK10
_queued_parameter_index++;
}

View File

@ -0,0 +1,81 @@
/*
compatibility header during transition to MAVLink 1.0
*/
#ifdef MAVLINK10
// in MAVLink 1.0 'waypoint' becomes 'mission'. We can remove these
// mappings once we are not trying to support both protocols
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT MAVLINK_MSG_ID_MISSION_CURRENT
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN MAVLINK_MSG_ID_MISSION_CURRENT_LEN
#define mavlink_msg_waypoint_current_send mavlink_msg_mission_current_send
#define mavlink_msg_waypoint_current_decode mavlink_msg_mission_current_decode
#define MAVLINK_MSG_ID_WAYPOINT_COUNT MAVLINK_MSG_ID_MISSION_COUNT
#define MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN MAVLINK_MSG_ID_MISSION_COUNT_LEN
#define mavlink_msg_waypoint_count_send mavlink_msg_mission_count_send
#define mavlink_msg_waypoint_count_decode mavlink_msg_mission_count_decode
#define mavlink_waypoint_count_t mavlink_mission_count_t
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST MAVLINK_MSG_ID_MISSION_REQUEST
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LEN
#define mavlink_msg_waypoint_request_send mavlink_msg_mission_request_send
#define mavlink_msg_waypoint_request_decode mavlink_msg_mission_request_decode
#define mavlink_waypoint_request_t mavlink_mission_request_t
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST MAVLINK_MSG_ID_MISSION_REQUEST_LIST
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN
#define mavlink_msg_waypoint_request_list_send mavlink_msg_mission_request_list_send
#define mavlink_msg_waypoint_request_list_decode mavlink_msg_mission_request_list_decode
#define mavlink_waypoint_request_list_t mavlink_mission_request_list_t
#define MAVLINK_MSG_ID_WAYPOINT MAVLINK_MSG_ID_MISSION_ITEM
#define MAVLINK_MSG_ID_WAYPOINT_LEN MAVLINK_MSG_ID_MISSION_ITEM_LEN
#define mavlink_msg_waypoint_send mavlink_msg_mission_item_send
#define mavlink_msg_waypoint_decode mavlink_msg_mission_item_decode
#define mavlink_waypoint_t mavlink_mission_item_t
#define MAVLINK_MSG_ID_WAYPOINT_ACK MAVLINK_MSG_ID_MISSION_ACK
#define MAVLINK_MSG_ID_WAYPOINT_ACK_LEN MAVLINK_MSG_ID_MISSION_ACK_LEN
#define mavlink_msg_waypoint_ack_send mavlink_msg_mission_ack_send
#define mavlink_msg_waypoint_ack_decode mavlink_msg_mission_ack_decode
#define mavlink_waypoint_ack_t mavlink_mission_ack_t
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL MAVLINK_MSG_ID_MISSION_CLEAR_ALL
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN
#define mavlink_msg_waypoint_clear_all_send mavlink_msg_mission_clear_all_send
#define mavlink_msg_waypoint_clear_all_decode mavlink_msg_mission_clear_all_decode
#define mavlink_waypoint_clear_all_t mavlink_mission_clear_all_t
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT MAVLINK_MSG_ID_MISSION_SET_CURRENT
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN
#define mavlink_msg_waypoint_set_current_send mavlink_msg_mission_set_current_send
#define mavlink_msg_waypoint_set_current_decode mavlink_msg_mission_set_current_decode
#define mavlink_waypoint_set_current_t mavlink_mission_set_current_t
static uint8_t mav_var_type(AP_Meta_class::Type_id t)
{
if (t == AP_Var::k_typeid_int8) {
return MAV_VAR_INT8;
}
if (t == AP_Var::k_typeid_int16) {
return MAV_VAR_INT16;
}
if (t == AP_Var::k_typeid_int32) {
return MAV_VAR_INT32;
}
// treat any others as float
return MAV_VAR_FLOAT;
}
#define MAV_FIXED_WING MAV_TYPE_FIXED_WING
#else
#define MAV_MISSION_ACCEPTED 0
#define MAV_MISSION_UNSUPPORTED 1
#define MAV_MISSION_UNSUPPORTED_FRAME 1
#define MAV_MISSION_ERROR 1
#define MAV_MISSION_INVALID_SEQUENCE 1
#endif

View File

@ -662,6 +662,11 @@
# define CLI_ENABLED ENABLED
#endif
// use this to disable the CLI slider switch
#ifndef CLI_SLIDER_ENABLED
# define CLI_SLIDER_ENABLED ENABLED
#endif
// delay to prevent Xbee bricking, in milliseconds
#ifndef MAVLINK_TELEMETRY_PORT_DELAY
# define MAVLINK_TELEMETRY_PORT_DELAY 2000

View File

@ -43,6 +43,14 @@ static const struct Menu::command main_menu_commands[] PROGMEM = {
// Create the top-level menu object.
MENU(main_menu, THISFIRMWARE, main_menu_commands);
// the user wants the CLI. It never exits
static void run_cli(void)
{
while (1) {
main_menu.run();
}
}
#endif // CLI_ENABLED
static void init_ardupilot()
@ -185,7 +193,7 @@ static void init_ardupilot()
// the system in an odd state, we don't let the user exit the top
// menu; they must reset in order to fly.
//
#if CLI_ENABLED == ENABLED
#if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED
if (digitalRead(SLIDE_SWITCH_PIN) == 0) {
digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED
Serial.printf_P(PSTR("\n"
@ -194,14 +202,13 @@ static void init_ardupilot()
"If using the Arduino Serial Monitor, ensure Line Ending is set to Carriage Return.\n"
"Type 'help' to list commands, 'exit' to leave a submenu.\n"
"Visit the 'setup' menu for first-time configuration.\n"));
for (;;) {
Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
main_menu.run();
}
Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n"));
run_cli();
}
#else
Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n"));
#endif // CLI_ENABLED
if(g.log_bitmask != 0){
// TODO - Here we will check on the length of the last log
// We don't want to create a bunch of little logs due to powering on and off

View File

@ -23,3 +23,4 @@
#include "APO_DefaultSetup.h"
#include <WProgram.h>; int main(void) {init();setup();for(;;) loop(); return 0; }
// vim:ts=4:sw=4:expandtab

View File

@ -18,6 +18,7 @@
// Vehicle Configuration
#include "CarStampede.h"
//#include "TankGeneric.h"
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"

View File

@ -28,10 +28,10 @@ static const uint8_t heartBeatTimeout = 3;
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
// baud rates
static uint32_t debugBaud = 57600;
static uint32_t telemBaud = 57600;
static uint32_t gpsBaud = 38400;
static uint32_t hilBaud = 57600;
static const uint32_t debugBaud = 57600;
static const uint32_t telemBaud = 57600;
static const uint32_t gpsBaud = 38400;
static const uint32_t hilBaud = 57600;
// optional sensors
static const bool gpsEnabled = false;
@ -41,7 +41,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD
// compass orientation: See AP_Compass_HMC5843.h for possible values
// battery monitoring
static const bool batteryMonitorEnabled = true;
static const bool batteryMonitorEnabled = false;
static const uint8_t batteryPin = 0;
static const float batteryVoltageDivRatio = 6;
static const float batteryMinVolt = 10.0;
@ -62,20 +62,26 @@ static const float loop2Rate = 1; // gcs slow
static const float loop3Rate = 0.1;
// gains
static const float steeringP = 1.0;
static const float steeringP = 0.1;
static const float steeringI = 0.0;
static const float steeringD = 0.0;
static const float steeringD = 0.1;
static const float steeringIMax = 0.0;
static const float steeringYMax = 3.0;
static const float steeringDFCut = 25;
static const float steeringYMax = 1;
static const float steeringDFCut = 25.0;
static const float throttleP = 0.0;
static const float throttleP = 0.1;
static const float throttleI = 0.0;
static const float throttleD = 0.0;
static const float throttleIMax = 0.0;
static const float throttleYMax = 0.0;
static const float throttleDFCut = 3.0;
static const float throttleYMax = 1;
static const float throttleDFCut = 0.0;
// guidance
static const float velCmd = 5;
static const float xt = 10;
static const float xtLim = 90;
#include "ControllerCar.h"
#endif /* CARSTAMPEDE_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -13,113 +13,69 @@
namespace apo {
class ControllerCar: public AP_Controller {
private:
AP_Var_group _group;
AP_Uint8 _mode;
enum {
k_chMode = k_radioChannelsStart, k_chStr, k_chThr
};
enum {
k_pidStr = k_controllersStart, k_pidThr
};
enum {
CH_MODE = 0, CH_STR, CH_THR
};
BlockPIDDfb pidStr;
BlockPID pidThr;
public:
ControllerCar(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
_group(k_cntrl, PSTR("CNTRL_")),
_mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax,steeringDFCut),
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut) {
_hal->debug->println_P(PSTR("initializing car controller"));
ControllerCar(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal,new AP_ArmingMechanism(hal,ch_thrust,ch_str,0.1,-0.9,0.9), ch_mode),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax,steeringDFCut),
pidThrust(new AP_Var_group(k_pidThrust, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut), _strCmd(0), _thrustCmd(0)
{
_hal->debug->println_P(PSTR("initializing car controller"));
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 7, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540,
1900, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_INOUT, false));
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
virtual void update(const float & dt) {
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 3, 1100, 1500,
1900, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThrust, PSTR("THR_"), APM_RC, 2, 1100, 1500,
1900, RC_MODE_INOUT, false));
}
// check for heartbeat
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n"));
return;
// if throttle less than 5% cut motor power
} else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) {
_mode = MAV_MODE_LOCKED;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_STANDBY);
return;
// if in live mode then set state to active
} else if (_hal->getMode() == MODE_LIVE) {
_hal->setState(MAV_STATE_ACTIVE);
// if in hardware in the loop (control) mode, set to hilsim
} else if (_hal->getMode() == MODE_HIL_CNTL) {
_hal->setState(MAV_STATE_HILSIM);
}
// read switch to set mode
if (_hal->rc[CH_MODE]->getRadioPosition() > 0) {
_mode = MAV_MODE_MANUAL;
} else {
_mode = MAV_MODE_AUTO;
}
private:
// methods
void manualLoop(const float dt) {
setAllRadioChannelsManually();
_strCmd = _hal->rc[ch_str]->getRadioPosition();
_thrustCmd = _hal->rc[ch_thrust]->getRadioPosition();
}
void autoLoop(const float dt) {
//_hal->debug->printf_P(PSTR("cont: ch1: %f\tch2: %f\n"),_hal->rc[ch_thrust]->getRadioPosition(), _hal->rc[ch_str]->getRadioPosition());
_strCmd = pidStr.update(_guide->getHeadingError(), _nav->getYawRate(), dt);
_thrustCmd = pidThrust.update(
_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt);
}
void setMotorsActive() {
// turn all motors off if below 0.1 throttle
if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) {
setAllRadioChannelsToNeutral();
} else {
_hal->rc[ch_thrust]->setPosition(_thrustCmd);
_hal->rc[ch_str]->setPosition(_strCmd);
}
}
// manual mode
switch (_mode) {
case MAV_MODE_MANUAL: {
setAllRadioChannelsManually();
//_hal->debug->println("manual");
break;
}
case MAV_MODE_AUTO: {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
_hal->rc[CH_STR]->setPosition(
pidStr.update(headingError, _nav->getYawRate(), dt));
_hal->rc[CH_THR]->setPosition(
pidThr.update(
_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt));
//_hal->debug->println("automode");
break;
}
default: {
setAllRadioChannelsToNeutral();
_mode = MAV_MODE_FAILSAFE;
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("unknown controller mode\n"));
break;
}
}
}
// attributes
enum {
ch_mode = 0, ch_str, ch_thrust
};
enum {
k_chMode = k_radioChannelsStart, k_chStr, k_chThrust
};
enum {
k_pidStr = k_controllersStart, k_pidThrust
};
BlockPIDDfb pidStr;
BlockPID pidThrust;
float _strCmd, _thrustCmd;
};
} // namespace apo
#endif /* CONTROLLERCAR_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -13,121 +13,79 @@
namespace apo {
class ControllerTank: public AP_Controller {
private:
AP_Var_group _group;
AP_Uint8 _mode;
enum {
k_chMode = k_radioChannelsStart, k_chLeft, k_chRight, k_chStr, k_chThr
};
enum {
k_pidStr = k_controllersStart, k_pidThr
};
enum {
CH_MODE = 0, CH_LEFT, CH_RIGHT, CH_STR, CH_THR
};
BlockPIDDfb pidStr;
BlockPID pidThr;
public:
ControllerTank(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
_group(k_cntrl, PSTR("CNTRL_")),
_mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax, steeringDFCut),
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut) {
_hal->debug->println_P(PSTR("initializing tank controller"));
ControllerTank(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal, new AP_ArmingMechanism(hal,ch_thrust,ch_str,0.1,-0.9,0.9),ch_mode),
pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP,
steeringI, steeringD, steeringIMax, steeringYMax, steeringDFCut),
pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP,
throttleI, throttleD, throttleIMax, throttleYMax,
throttleDFCut), _headingOutput(0), _throttleOutput(0) {
_hal->debug->println_P(PSTR("initializing tank controller"));
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, 1500,
1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1500,
1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_IN, false));
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
void mix(float headingOutput, float throttleOutput) {
_hal->rc[CH_LEFT]->setPosition(throttleOutput + headingOutput);
_hal->rc[CH_RIGHT]->setPosition(throttleOutput - headingOutput);
}
virtual void update(const float & dt) {
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, 1500,
1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1500,
1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500,
1900, RC_MODE_IN, false));
}
// check for heartbeat
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n"));
return;
// if throttle less than 5% cut motor power
} else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) {
_mode = MAV_MODE_LOCKED;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_STANDBY);
return;
// if in live mode then set state to active
} else if (_hal->getMode() == MODE_LIVE) {
_hal->setState(MAV_STATE_ACTIVE);
// if in hardware in the loop (control) mode, set to hilsim
} else if (_hal->getMode() == MODE_HIL_CNTL) {
_hal->setState(MAV_STATE_HILSIM);
}
// read switch to set mode
if (_hal->rc[CH_MODE]->getRadioPosition() > 0) {
_mode = MAV_MODE_MANUAL;
} else {
_mode = MAV_MODE_AUTO;
}
private:
// methods
void manualLoop(const float dt) {
setAllRadioChannelsManually();
_headingOutput = _hal->rc[ch_str]->getPosition();
_throttleOutput = _hal->rc[ch_thrust]->getPosition();
}
void autoLoop(const float dt) {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
_headingOutput = pidStr.update(headingError, _nav->getYawRate(), dt);
_throttleOutput = pidThr.update(_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt);
}
void setMotorsActive() {
// turn all motors off if below 0.1 throttle
if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) {
setAllRadioChannelsToNeutral();
} else {
_hal->rc[ch_left]->setPosition(_throttleOutput + _headingOutput);
_hal->rc[ch_right]->setPosition(_throttleOutput - _headingOutput);
}
}
// manual mode
switch (_mode) {
case MAV_MODE_MANUAL: {
setAllRadioChannelsManually();
mix(_hal->rc[CH_STR]->getPosition(),
_hal->rc[CH_THR]->getPosition());
break;
}
case MAV_MODE_AUTO: {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
mix(pidStr.update(headingError, _nav->getYawRate(), dt),
pidThr.update(_guide->getGroundSpeedCommand()
- _nav->getGroundSpeed(), dt));
//_hal->debug->println("automode");
break;
}
default: {
setAllRadioChannelsToNeutral();
_mode = MAV_MODE_FAILSAFE;
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("unknown controller mode\n"));
break;
}
}
}
// attributes
enum {
k_chMode = k_radioChannelsStart, k_chLeft, k_chRight, k_chStr, k_chThr
};
enum {
k_pidStr = k_controllersStart, k_pidThr
};
enum {
ch_mode = 0, ch_left, ch_right, ch_str, ch_thrust
};
BlockPIDDfb pidStr;
BlockPID pidThr;
float _headingOutput;
float _throttleOutput;
};
} // namespace apo
#endif /* CONTROLLERTANK_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -5,6 +5,8 @@
* Author: jgoppert
*/
// NOT CURRENTLY WORKING
#ifndef TANKGENERIC_H_
#define TANKGENERIC_H_
@ -27,10 +29,10 @@ static const uint8_t heartBeatTimeout = 3;
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
// baud rates
static uint32_t debugBaud = 57600;
static uint32_t telemBaud = 57600;
static uint32_t gpsBaud = 38400;
static uint32_t hilBaud = 57600;
static const uint32_t debugBaud = 57600;
static const uint32_t telemBaud = 57600;
static const uint32_t gpsBaud = 38400;
static const uint32_t hilBaud = 57600;
// optional sensors
static const bool gpsEnabled = false;
@ -75,6 +77,12 @@ const float throttleIMax = 0.0;
const float throttleYMax = 0.0;
const float throttleDFCut = 3.0;
// guidance
static const float velCmd = 5;
static const float xt = 10;
static const float xtLim = 90;
#include "ControllerTank.h"
#endif /* TANKGENERIC_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -183,6 +183,12 @@
</Compile>
<Compile Include="ArduinoDetect.cs" />
<Compile Include="AviWriter.cs" />
<Compile Include="Camera.cs">
<SubType>Form</SubType>
</Compile>
<Compile Include="Camera.Designer.cs">
<DependentUpon>Camera.cs</DependentUpon>
</Compile>
<Compile Include="Capture.cs" />
<Compile Include="CommsSerialInterface.cs" />
<Compile Include="CommsSerialPort.cs">
@ -350,6 +356,9 @@
<DependentUpon>AGauge.cs</DependentUpon>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="Camera.resx">
<DependentUpon>Camera.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Configuration.ru-RU.resx">
<DependentUpon>Configuration.cs</DependentUpon>
</EmbeddedResource>

View File

@ -0,0 +1,421 @@
namespace ArdupilotMega
{
partial class Camera
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
#region Windows Form Designer generated code
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
private void InitializeComponent()
{
this.num_agl = new System.Windows.Forms.NumericUpDown();
this.num_megapixel = new System.Windows.Forms.NumericUpDown();
this.label2 = new System.Windows.Forms.Label();
this.label3 = new System.Windows.Forms.Label();
this.num_focallength = new System.Windows.Forms.NumericUpDown();
this.label4 = new System.Windows.Forms.Label();
this.num_focalmultip = new System.Windows.Forms.NumericUpDown();
this.TXT_fovH = new System.Windows.Forms.TextBox();
this.TXT_fovV = new System.Windows.Forms.TextBox();
this.TXT_fovD = new System.Windows.Forms.TextBox();
this.TXT_fovAD = new System.Windows.Forms.TextBox();
this.TXT_fovAV = new System.Windows.Forms.TextBox();
this.TXT_fovAH = new System.Windows.Forms.TextBox();
this.TXT_cmpixel = new System.Windows.Forms.TextBox();
this.TXT_imgwidth = new System.Windows.Forms.TextBox();
this.TXT_imgheight = new System.Windows.Forms.TextBox();
this.label1 = new System.Windows.Forms.Label();
this.label5 = new System.Windows.Forms.Label();
this.label6 = new System.Windows.Forms.Label();
this.label7 = new System.Windows.Forms.Label();
this.label8 = new System.Windows.Forms.Label();
this.label9 = new System.Windows.Forms.Label();
this.label10 = new System.Windows.Forms.Label();
this.label11 = new System.Windows.Forms.Label();
this.label12 = new System.Windows.Forms.Label();
this.label13 = new System.Windows.Forms.Label();
this.label14 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.num_agl)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.num_megapixel)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.num_focallength)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.num_focalmultip)).BeginInit();
this.SuspendLayout();
//
// num_agl
//
this.num_agl.Location = new System.Drawing.Point(12, 12);
this.num_agl.Maximum = new decimal(new int[] {
10000,
0,
0,
0});
this.num_agl.Name = "num_agl";
this.num_agl.Size = new System.Drawing.Size(120, 20);
this.num_agl.TabIndex = 1;
this.num_agl.Value = new decimal(new int[] {
200,
0,
0,
0});
this.num_agl.ValueChanged += new System.EventHandler(this.num_agl_ValueChanged);
//
// num_megapixel
//
this.num_megapixel.DecimalPlaces = 1;
this.num_megapixel.Increment = new decimal(new int[] {
5,
0,
0,
65536});
this.num_megapixel.Location = new System.Drawing.Point(13, 38);
this.num_megapixel.Name = "num_megapixel";
this.num_megapixel.Size = new System.Drawing.Size(120, 20);
this.num_megapixel.TabIndex = 2;
this.num_megapixel.Value = new decimal(new int[] {
8,
0,
0,
0});
this.num_megapixel.ValueChanged += new System.EventHandler(this.num_megapixel_ValueChanged);
//
// label2
//
this.label2.AutoSize = true;
this.label2.Location = new System.Drawing.Point(140, 19);
this.label2.Name = "label2";
this.label2.Size = new System.Drawing.Size(72, 13);
this.label2.TabIndex = 4;
this.label2.Text = "Height m (agl)";
//
// label3
//
this.label3.AutoSize = true;
this.label3.Location = new System.Drawing.Point(140, 45);
this.label3.Name = "label3";
this.label3.Size = new System.Drawing.Size(95, 13);
this.label3.TabIndex = 5;
this.label3.Text = "MegaPixel Camera";
//
// num_focallength
//
this.num_focallength.DecimalPlaces = 1;
this.num_focallength.Increment = new decimal(new int[] {
5,
0,
0,
65536});
this.num_focallength.Location = new System.Drawing.Point(245, 12);
this.num_focallength.Maximum = new decimal(new int[] {
180,
0,
0,
0});
this.num_focallength.Minimum = new decimal(new int[] {
1,
0,
0,
0});
this.num_focallength.Name = "num_focallength";
this.num_focallength.Size = new System.Drawing.Size(120, 20);
this.num_focallength.TabIndex = 6;
this.num_focallength.Value = new decimal(new int[] {
35,
0,
0,
0});
this.num_focallength.ValueChanged += new System.EventHandler(this.num_focallength_ValueChanged);
//
// label4
//
this.label4.AutoSize = true;
this.label4.Location = new System.Drawing.Point(242, 72);
this.label4.Name = "label4";
this.label4.Size = new System.Drawing.Size(99, 13);
this.label4.TabIndex = 8;
this.label4.Text = "2 x tan-1( l / (2 x f) )";
//
// num_focalmultip
//
this.num_focalmultip.DecimalPlaces = 1;
this.num_focalmultip.Increment = new decimal(new int[] {
1,
0,
0,
65536});
this.num_focalmultip.Location = new System.Drawing.Point(245, 38);
this.num_focalmultip.Maximum = new decimal(new int[] {
5,
0,
0,
0});
this.num_focalmultip.Minimum = new decimal(new int[] {
1,
0,
0,
65536});
this.num_focalmultip.Name = "num_focalmultip";
this.num_focalmultip.Size = new System.Drawing.Size(120, 20);
this.num_focalmultip.TabIndex = 9;
this.num_focalmultip.Value = new decimal(new int[] {
15,
0,
0,
65536});
this.num_focalmultip.ValueChanged += new System.EventHandler(this.num_focalmultip_ValueChanged);
//
// TXT_fovH
//
this.TXT_fovH.Location = new System.Drawing.Point(72, 138);
this.TXT_fovH.Name = "TXT_fovH";
this.TXT_fovH.Size = new System.Drawing.Size(100, 20);
this.TXT_fovH.TabIndex = 10;
//
// TXT_fovV
//
this.TXT_fovV.Location = new System.Drawing.Point(72, 165);
this.TXT_fovV.Name = "TXT_fovV";
this.TXT_fovV.Size = new System.Drawing.Size(100, 20);
this.TXT_fovV.TabIndex = 11;
//
// TXT_fovD
//
this.TXT_fovD.Location = new System.Drawing.Point(72, 192);
this.TXT_fovD.Name = "TXT_fovD";
this.TXT_fovD.Size = new System.Drawing.Size(100, 20);
this.TXT_fovD.TabIndex = 12;
//
// TXT_fovAD
//
this.TXT_fovAD.Location = new System.Drawing.Point(286, 192);
this.TXT_fovAD.Name = "TXT_fovAD";
this.TXT_fovAD.Size = new System.Drawing.Size(100, 20);
this.TXT_fovAD.TabIndex = 15;
//
// TXT_fovAV
//
this.TXT_fovAV.Location = new System.Drawing.Point(286, 165);
this.TXT_fovAV.Name = "TXT_fovAV";
this.TXT_fovAV.Size = new System.Drawing.Size(100, 20);
this.TXT_fovAV.TabIndex = 14;
//
// TXT_fovAH
//
this.TXT_fovAH.Location = new System.Drawing.Point(286, 138);
this.TXT_fovAH.Name = "TXT_fovAH";
this.TXT_fovAH.Size = new System.Drawing.Size(100, 20);
this.TXT_fovAH.TabIndex = 13;
//
// TXT_cmpixel
//
this.TXT_cmpixel.Location = new System.Drawing.Point(176, 218);
this.TXT_cmpixel.Name = "TXT_cmpixel";
this.TXT_cmpixel.Size = new System.Drawing.Size(100, 20);
this.TXT_cmpixel.TabIndex = 16;
//
// TXT_imgwidth
//
this.TXT_imgwidth.Location = new System.Drawing.Point(93, 244);
this.TXT_imgwidth.Name = "TXT_imgwidth";
this.TXT_imgwidth.Size = new System.Drawing.Size(100, 20);
this.TXT_imgwidth.TabIndex = 17;
//
// TXT_imgheight
//
this.TXT_imgheight.Location = new System.Drawing.Point(255, 244);
this.TXT_imgheight.Name = "TXT_imgheight";
this.TXT_imgheight.Size = new System.Drawing.Size(100, 20);
this.TXT_imgheight.TabIndex = 18;
//
// label1
//
this.label1.AutoSize = true;
this.label1.Location = new System.Drawing.Point(371, 19);
this.label1.Name = "label1";
this.label1.Size = new System.Drawing.Size(69, 13);
this.label1.TabIndex = 19;
this.label1.Text = "Focal Length";
//
// label5
//
this.label5.AutoSize = true;
this.label5.Location = new System.Drawing.Point(371, 45);
this.label5.Name = "label5";
this.label5.Size = new System.Drawing.Size(88, 13);
this.label5.TabIndex = 20;
this.label5.Text = "Frame Muli factor";
//
// label6
//
this.label6.AutoSize = true;
this.label6.Location = new System.Drawing.Point(9, 145);
this.label6.Name = "label6";
this.label6.Size = new System.Drawing.Size(36, 13);
this.label6.TabIndex = 21;
this.label6.Text = "Dist H";
//
// label7
//
this.label7.AutoSize = true;
this.label7.Location = new System.Drawing.Point(235, 145);
this.label7.Name = "label7";
this.label7.Size = new System.Drawing.Size(45, 13);
this.label7.TabIndex = 22;
this.label7.Text = "Angle H";
//
// label8
//
this.label8.AutoSize = true;
this.label8.Location = new System.Drawing.Point(236, 172);
this.label8.Name = "label8";
this.label8.Size = new System.Drawing.Size(44, 13);
this.label8.TabIndex = 23;
this.label8.Text = "Angle V";
//
// label9
//
this.label9.AutoSize = true;
this.label9.Location = new System.Drawing.Point(235, 199);
this.label9.Name = "label9";
this.label9.Size = new System.Drawing.Size(45, 13);
this.label9.TabIndex = 24;
this.label9.Text = "Angle D";
//
// label10
//
this.label10.AutoSize = true;
this.label10.Location = new System.Drawing.Point(10, 172);
this.label10.Name = "label10";
this.label10.Size = new System.Drawing.Size(35, 13);
this.label10.TabIndex = 25;
this.label10.Text = "Dist V";
//
// label11
//
this.label11.AutoSize = true;
this.label11.Location = new System.Drawing.Point(10, 199);
this.label11.Name = "label11";
this.label11.Size = new System.Drawing.Size(36, 13);
this.label11.TabIndex = 26;
this.label11.Text = "Dist D";
//
// label12
//
this.label12.AutoSize = true;
this.label12.Location = new System.Drawing.Point(125, 225);
this.label12.Name = "label12";
this.label12.Size = new System.Drawing.Size(50, 13);
this.label12.TabIndex = 27;
this.label12.Text = "CM/Pixel";
//
// label13
//
this.label13.AutoSize = true;
this.label13.Location = new System.Drawing.Point(37, 251);
this.label13.Name = "label13";
this.label13.Size = new System.Drawing.Size(39, 13);
this.label13.TabIndex = 28;
this.label13.Text = "Pixel X";
//
// label14
//
this.label14.AutoSize = true;
this.label14.Location = new System.Drawing.Point(199, 253);
this.label14.Name = "label14";
this.label14.Size = new System.Drawing.Size(39, 13);
this.label14.TabIndex = 29;
this.label14.Text = "Pixel Y";
//
// Camera
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(473, 275);
this.Controls.Add(this.label14);
this.Controls.Add(this.label13);
this.Controls.Add(this.label12);
this.Controls.Add(this.label11);
this.Controls.Add(this.label10);
this.Controls.Add(this.label9);
this.Controls.Add(this.label8);
this.Controls.Add(this.label7);
this.Controls.Add(this.label6);
this.Controls.Add(this.label5);
this.Controls.Add(this.label1);
this.Controls.Add(this.TXT_imgheight);
this.Controls.Add(this.TXT_imgwidth);
this.Controls.Add(this.TXT_cmpixel);
this.Controls.Add(this.TXT_fovAD);
this.Controls.Add(this.TXT_fovAV);
this.Controls.Add(this.TXT_fovAH);
this.Controls.Add(this.TXT_fovD);
this.Controls.Add(this.TXT_fovV);
this.Controls.Add(this.TXT_fovH);
this.Controls.Add(this.num_focalmultip);
this.Controls.Add(this.label4);
this.Controls.Add(this.num_focallength);
this.Controls.Add(this.label3);
this.Controls.Add(this.label2);
this.Controls.Add(this.num_megapixel);
this.Controls.Add(this.num_agl);
this.Name = "Camera";
this.Text = "Camera";
((System.ComponentModel.ISupportInitialize)(this.num_agl)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.num_megapixel)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.num_focallength)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.num_focalmultip)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
}
#endregion
private System.Windows.Forms.NumericUpDown num_agl;
private System.Windows.Forms.NumericUpDown num_megapixel;
private System.Windows.Forms.Label label2;
private System.Windows.Forms.Label label3;
private System.Windows.Forms.NumericUpDown num_focallength;
private System.Windows.Forms.Label label4;
private System.Windows.Forms.NumericUpDown num_focalmultip;
private System.Windows.Forms.TextBox TXT_fovH;
private System.Windows.Forms.TextBox TXT_fovV;
private System.Windows.Forms.TextBox TXT_fovD;
private System.Windows.Forms.TextBox TXT_fovAD;
private System.Windows.Forms.TextBox TXT_fovAV;
private System.Windows.Forms.TextBox TXT_fovAH;
private System.Windows.Forms.TextBox TXT_cmpixel;
private System.Windows.Forms.TextBox TXT_imgwidth;
private System.Windows.Forms.TextBox TXT_imgheight;
private System.Windows.Forms.Label label1;
private System.Windows.Forms.Label label5;
private System.Windows.Forms.Label label6;
private System.Windows.Forms.Label label7;
private System.Windows.Forms.Label label8;
private System.Windows.Forms.Label label9;
private System.Windows.Forms.Label label10;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.Label label12;
private System.Windows.Forms.Label label13;
private System.Windows.Forms.Label label14;
}
}

View File

@ -0,0 +1,139 @@
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Data;
using System.Drawing;
using System.Linq;
using System.Text;
using System.Windows.Forms;
namespace ArdupilotMega
{
public partial class Camera : Form
{
float mm_2_feet = 1 / 304.8f;
float feet_2_mm = 304.8f;
const float rad2deg = (float)(180 / Math.PI);
const float deg2rad = (float)(1.0 / rad2deg);
public Camera()
{
InitializeComponent();
}
private void numericUpDown1_ValueChanged(object sender, EventArgs e)
{
doCalc();
}
void doCalc()
{
var film_width = 36.0f;
var film_height = 27.0f;
var film_diag = 0.0f;
var flen = (float)num_focallength.Value;
var flen_mult = (float)num_focalmultip.Value;
var subj_dist = (float)num_agl.Value;
//if (isNaN(flen_mult) || flen_mult<=0)
{
//f.flen_mult = 1;
//flen_mult = 1;
}
// convert distance to mm
/*
if (f.units.value.search(/feet/i) != -1)
{
//user input in feet
subj_dist = subj_dist * feet_2_mm;
}
else */
{
//user input in m
subj_dist = subj_dist * 1000;
}
//Account for focal length multiplier (actually, a film/sensor size multiplier)
film_width = film_width / flen_mult;
film_height = film_height / flen_mult;
film_diag = (int)(Math.Sqrt((film_width * film_width) + (film_height * film_height)));
var half_fov_h = (Math.Atan(film_width / (2 * flen)));
var fov_h = 2 * (subj_dist * Math.Tan(half_fov_h));
var half_fov_v = (Math.Atan(film_height / (2 * flen)));
var fov_v = 2 * (subj_dist * Math.Tan(half_fov_v));
var half_fov_d = (Math.Atan(film_diag / (2 * flen)));
var fov_d = 2 * (subj_dist * Math.Tan(half_fov_d));
//convert answer (currently in mm) back to feet
fov_h = fov_h * mm_2_feet;
fov_v = fov_v * mm_2_feet;
fov_d = fov_d * mm_2_feet;
/*
if (f.units.value.search(/feet/i) != -1)
{
f.fov_h.value = feet_inches(fov_h);
f.fov_v.value = feet_inches(fov_v);
f.fov_d.value = feet_inches(fov_d);
}
else */
{
TXT_fovH.Text = meters(fov_h);
TXT_fovV.Text = meters(fov_v);
TXT_fovD.Text = meters(fov_d);
TXT_fovAH.Text = (half_fov_h * 2 * rad2deg).ToString("0.00");
TXT_fovAV.Text = (half_fov_v * 2 * rad2deg).ToString("0.00");
TXT_fovAD.Text = (half_fov_d * 2 * rad2deg).ToString("0.00");
float test1 = (float)Math.Sqrt((float)num_megapixel.Value * 1000000 * (film_height / film_width));
TXT_imgwidth.Text = test1.ToString("0");
TXT_imgheight.Text = (((float)num_megapixel.Value * 1000000) / test1).ToString("0");
TXT_cmpixel.Text = (((fov_h * feet_2_mm) / 10.0) / test1).ToString("0.000 cm");
}
}
//Takes a distance in feet and converts to string representation in meters/cm
string meters(double aNumber)
{
//if (isNaN(aNumber))
//return aNumber;
var mm = aNumber * feet_2_mm;
var m = Math.Floor(mm / 1000);
var cm = (mm / 10) % 100;
return m + "m " + cm.ToString("0.00") + "cm";
}
private void num_agl_ValueChanged(object sender, EventArgs e)
{
doCalc();
}
private void num_megapixel_ValueChanged(object sender, EventArgs e)
{
doCalc();
}
private void num_focallength_ValueChanged(object sender, EventArgs e)
{
doCalc();
}
private void num_focalmultip_ValueChanged(object sender, EventArgs e)
{
doCalc();
}
}
}

View File

@ -0,0 +1,120 @@
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
</root>

View File

@ -147,6 +147,10 @@ namespace ArdupilotMega
public ushort rcoverridech2 { get; set; }
public ushort rcoverridech3 { get; set; }
public ushort rcoverridech4 { get; set; }
public ushort rcoverridech5 { get; set; }
public ushort rcoverridech6 { get; set; }
public ushort rcoverridech7 { get; set; }
public ushort rcoverridech8 { get; set; }
// current firmware
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane;
@ -187,10 +191,15 @@ namespace ArdupilotMega
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs)
{
UpdateCurrentSettings(bs, false);
UpdateCurrentSettings(bs, false, MainV2.comPort);
}
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow)
{
UpdateCurrentSettings(bs, false, MainV2.comPort);
}
public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow, MAVLink mavinterface)
{
if (DateTime.Now > lastupdate.AddMilliseconds(19) || updatenow) // 50 hz
{
@ -203,10 +212,10 @@ namespace ArdupilotMega
}
// Console.WriteLine("Updating CurrentState " + DateTime.Now.Millisecond);
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
{
string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6);
string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6);
int ind = logdata.IndexOf('\0');
if (ind != -1)
@ -217,16 +226,16 @@ namespace ArdupilotMega
}
messages.Add(logdata + "\n");
MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null;
mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] != null) // hil
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] != null) // hil
{
var hil = new ArdupilotMega.MAVLink.__mavlink_rc_channels_scaled_t();
object temp = hil;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED], ref temp, 6);
hil = (MAVLink.__mavlink_rc_channels_scaled_t)(temp);
@ -242,13 +251,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] != null)
{
MAVLink.__mavlink_nav_controller_output_t nav = new MAVLink.__mavlink_nav_controller_output_t();
object temp = nav;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT], ref temp, 6);
nav = (MAVLink.__mavlink_nav_controller_output_t)(temp);
@ -264,13 +273,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] = null;
}
if (MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] != null)
if (mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] != null)
{
ArdupilotMega.MAVLink.__mavlink_sys_status_t sysstatus = new ArdupilotMega.MAVLink.__mavlink_sys_status_t();
object temp = sysstatus;
MAVLink.ByteArrayToStructure(MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS], ref temp, 6);
sysstatus = (ArdupilotMega.MAVLink.__mavlink_sys_status_t)(temp);
@ -377,13 +386,13 @@ namespace ArdupilotMega
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] != null)
{
var att = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
object temp = att;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE], ref temp, 6);
att = (MAVLink.__mavlink_attitude_t)(temp);
@ -396,13 +405,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] != null)
{
var gps = new MAVLink.__mavlink_gps_raw_t();
object temp = gps;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW], ref temp, 6);
gps = (MAVLink.__mavlink_gps_raw_t)(temp);
@ -421,26 +430,26 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS] != null)
{
var gps = new MAVLink.__mavlink_gps_status_t();
object temp = gps;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS], ref temp, 6);
gps = (MAVLink.__mavlink_gps_status_t)(temp);
satcount = gps.satellites_visible;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT] != null)
{
var loc = new MAVLink.__mavlink_global_position_int_t();
object temp = loc;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT], ref temp, 6);
loc = (MAVLink.__mavlink_global_position_int_t)(temp);
@ -449,13 +458,13 @@ namespace ArdupilotMega
lng = loc.lon / 10000000.0f;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION] != null)
{
var loc = new MAVLink.__mavlink_global_position_t();
object temp = loc;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION], ref temp, 6);
loc = (MAVLink.__mavlink_global_position_t)(temp);
@ -464,13 +473,13 @@ namespace ArdupilotMega
lng = loc.lon;
}
if (MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] != null)
if (mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] != null)
{
ArdupilotMega.MAVLink.__mavlink_waypoint_current_t wpcur = new ArdupilotMega.MAVLink.__mavlink_waypoint_current_t();
object temp = wpcur;
MAVLink.ByteArrayToStructure(MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT], ref temp, 6);
wpcur = (ArdupilotMega.MAVLink.__mavlink_waypoint_current_t)(temp);
@ -486,13 +495,13 @@ namespace ArdupilotMega
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] != null)
{
var rcin = new MAVLink.__mavlink_rc_channels_raw_t();
object temp = rcin;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW], ref temp, 6);
rcin = (MAVLink.__mavlink_rc_channels_raw_t)(temp);
@ -508,13 +517,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] != null)
{
var servoout = new MAVLink.__mavlink_servo_output_raw_t();
object temp = servoout;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW], ref temp, 6);
servoout = (MAVLink.__mavlink_servo_output_raw_t)(temp);
@ -530,13 +539,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] != null)
{
var imu = new MAVLink.__mavlink_raw_imu_t();
object temp = imu;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU], ref temp, 6);
imu = (MAVLink.__mavlink_raw_imu_t)(temp);
@ -551,13 +560,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU] != null)
{
var imu = new MAVLink.__mavlink_scaled_imu_t();
object temp = imu;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU], ref temp, 6);
imu = (MAVLink.__mavlink_scaled_imu_t)(temp);
@ -572,13 +581,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] != null)
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] != null)
{
MAVLink.__mavlink_vfr_hud_t vfr = new MAVLink.__mavlink_vfr_hud_t();
object temp = vfr;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD], ref temp, 6);
vfr = (MAVLink.__mavlink_vfr_hud_t)(temp);
@ -602,13 +611,13 @@ namespace ArdupilotMega
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] = null;
}
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO] != null) // hil
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO] != null) // hil
{
var mem = new ArdupilotMega.MAVLink.__mavlink_meminfo_t();
object temp = mem;
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO], ref temp, 6);
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO], ref temp, 6);
mem = (MAVLink.__mavlink_meminfo_t)(temp);

View File

@ -46,7 +46,7 @@ autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' bu
autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used

View File

@ -46,7 +46,7 @@ autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' bu
autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined
autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined
autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used

View File

@ -9,11 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
@ -34,7 +34,7 @@ autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' de
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used

View File

@ -677,9 +677,9 @@
000003a0 t read_battery()
0000045c T update_yaw_mode()
0000046e T update_roll_pitch_mode()
0000052e t heli_move_swash(int, int, int, int)
0000053e t heli_move_swash(int, int, int, int)
000005cc t __static_initialization_and_destruction_0(int, int)
00000640 t init_ardupilot()
00000620 t init_ardupilot()
0000071a t update_nav_wp()
000007ec t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()

View File

@ -9,11 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77:
/root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()':
/root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning
/root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)':
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function
/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function
autogenerated: At global scope:
autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined
@ -34,7 +34,7 @@ autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' de
autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used
/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used
/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used
autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined
autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined
/root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used

View File

@ -677,9 +677,9 @@
000003a0 t read_battery()
0000045c T update_yaw_mode()
0000046e T update_roll_pitch_mode()
0000052e t heli_move_swash(int, int, int, int)
0000053e t heli_move_swash(int, int, int, int)
000005cc t __static_initialization_and_destruction_0(int, int)
0000063e t init_ardupilot()
0000061e t init_ardupilot()
0000071a t update_nav_wp()
000007e8 t setup_heli(unsigned char, Menu::arg const*)
00000870 t process_next_command()

View File

@ -99,6 +99,7 @@
<desc>
#define AUTO_RESET_LOITER 0
#define FRAME_CONFIG HELI_FRAME
#define INSTANT_PWM ENABLED
// DEFAULT PIDS

View File

@ -1 +1,36 @@
Already up-to-date.
From https://code.google.com/p/ardupilot-mega
8a21477..b0bfa54 APM_Camera -> origin/APM_Camera
6f44fff..076459c master -> origin/master
Updating 6f44fff..076459c
Fast-forward
ArduCopter/control_modes.pde | 16 +
ArduCopter/defines.h | 1 +
ArduCopter/system.pde | 4 +
ArduPlane/ArduPlane.pde | 10 +-
ArduPlane/Parameters.h | 3 +
ArduPlane/config.h | 8 +
Tools/ArduTracker/tags |148411 --------------------
Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 2 +
Tools/ArdupilotMegaPlanner/Log.cs | 174 +-
Tools/ArdupilotMegaPlanner/MainV2.cs | 9 +-
.../Properties/AssemblyInfo.cs | 2 +-
.../bin/Release/ArdupilotMegaPlanner.application | 2 +-
.../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194432 -> 2194944 bytes
Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes
Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes
.../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes
.../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes
apo/ControllerQuad.h | 51 +-
apo/QuadArducopter.h | 10 +-
libraries/APO/AP_ArmingMechanism.cpp | 57 +
libraries/APO/AP_ArmingMechanism.h | 67 +
libraries/APO/AP_BatteryMonitor.cpp | 2 +
libraries/APO/AP_BatteryMonitor.h | 58 +-
libraries/APO/AP_Guide.h | 1 +
libraries/APO/AP_HardwareAbstractionLayer.h | 13 +
libraries/APO/AP_Navigator.cpp | 20 +-
libraries/Desktop/support/FastSerial.cpp | 283 +-
27 files changed, 517 insertions(+), 148687 deletions(-)
delete mode 100644 Tools/ArduTracker/tags
create mode 100644 libraries/APO/AP_ArmingMechanism.cpp
create mode 100644 libraries/APO/AP_ArmingMechanism.h

View File

@ -289,8 +289,6 @@ namespace ArdupilotMega.GCSViews
internal void processToScreen()
{
Params.Rows.Clear();
// process hashdefines and update display
@ -343,7 +341,7 @@ namespace ArdupilotMega.GCSViews
{
try
{
toolTip1.SetToolTip(ctl, tooltips[value].ToString());
toolTip1.SetToolTip(ctl, ((paramsettings)tooltips[value]).desc);
}
catch { }
}

View File

@ -563,7 +563,7 @@ namespace ArdupilotMega.GCSViews
this.Refresh();
Console.WriteLine("Downloaded");
}
catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.Message); return; }
catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.ToString()); return; }
UploadFlash(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex", board);
}

View File

@ -50,6 +50,11 @@
this.BUT_playlog = new ArdupilotMega.MyButton();
this.BUT_loadtelem = new ArdupilotMega.MyButton();
this.tableMap = new System.Windows.Forms.TableLayoutPanel();
this.splitContainer1 = new System.Windows.Forms.SplitContainer();
this.zg1 = new ZedGraph.ZedGraphControl();
this.lbl_winddir = new ArdupilotMega.MyLabel();
this.lbl_windvel = new ArdupilotMega.MyLabel();
this.gMapControl1 = new GMap.NET.WindowsForms.GMapControl();
this.panel1 = new System.Windows.Forms.Panel();
this.TXT_lat = new ArdupilotMega.MyLabel();
this.Zoomlevel = new System.Windows.Forms.NumericUpDown();
@ -58,11 +63,6 @@
this.TXT_alt = new ArdupilotMega.MyLabel();
this.CHK_autopan = new System.Windows.Forms.CheckBox();
this.CB_tuning = new System.Windows.Forms.CheckBox();
this.panel2 = new System.Windows.Forms.Panel();
this.lbl_windvel = new ArdupilotMega.MyLabel();
this.lbl_winddir = new ArdupilotMega.MyLabel();
this.gMapControl1 = new GMap.NET.WindowsForms.GMapControl();
this.zg1 = new ZedGraph.ZedGraphControl();
this.dataGridViewImageColumn1 = new System.Windows.Forms.DataGridViewImageColumn();
this.dataGridViewImageColumn2 = new System.Windows.Forms.DataGridViewImageColumn();
this.ZedGraphTimer = new System.Windows.Forms.Timer(this.components);
@ -84,9 +84,11 @@
((System.ComponentModel.ISupportInitialize)(this.NUM_playbackspeed)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.tracklog)).BeginInit();
this.tableMap.SuspendLayout();
this.splitContainer1.Panel1.SuspendLayout();
this.splitContainer1.Panel2.SuspendLayout();
this.splitContainer1.SuspendLayout();
this.panel1.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).BeginInit();
this.panel2.SuspendLayout();
this.SuspendLayout();
//
// contextMenuStrip1
@ -1042,10 +1044,80 @@
// tableMap
//
resources.ApplyResources(this.tableMap, "tableMap");
this.tableMap.Controls.Add(this.splitContainer1, 0, 0);
this.tableMap.Controls.Add(this.panel1, 0, 1);
this.tableMap.Controls.Add(this.panel2, 0, 0);
this.tableMap.Name = "tableMap";
//
// splitContainer1
//
resources.ApplyResources(this.splitContainer1, "splitContainer1");
this.splitContainer1.Name = "splitContainer1";
//
// splitContainer1.Panel1
//
this.splitContainer1.Panel1.Controls.Add(this.zg1);
this.splitContainer1.Panel1Collapsed = true;
//
// splitContainer1.Panel2
//
this.splitContainer1.Panel2.Controls.Add(this.lbl_winddir);
this.splitContainer1.Panel2.Controls.Add(this.lbl_windvel);
this.splitContainer1.Panel2.Controls.Add(this.gMapControl1);
//
// zg1
//
resources.ApplyResources(this.zg1, "zg1");
this.zg1.Name = "zg1";
this.zg1.ScrollGrace = 0D;
this.zg1.ScrollMaxX = 0D;
this.zg1.ScrollMaxY = 0D;
this.zg1.ScrollMaxY2 = 0D;
this.zg1.ScrollMinX = 0D;
this.zg1.ScrollMinY = 0D;
this.zg1.ScrollMinY2 = 0D;
this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick);
//
// lbl_winddir
//
this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0"));
resources.ApplyResources(this.lbl_winddir, "lbl_winddir");
this.lbl_winddir.Name = "lbl_winddir";
this.lbl_winddir.resize = true;
this.toolTip1.SetToolTip(this.lbl_winddir, resources.GetString("lbl_winddir.ToolTip"));
//
// lbl_windvel
//
this.lbl_windvel.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_vel", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Vel: 0"));
resources.ApplyResources(this.lbl_windvel, "lbl_windvel");
this.lbl_windvel.Name = "lbl_windvel";
this.lbl_windvel.resize = true;
this.toolTip1.SetToolTip(this.lbl_windvel, resources.GetString("lbl_windvel.ToolTip"));
//
// gMapControl1
//
this.gMapControl1.BackColor = System.Drawing.Color.Transparent;
this.gMapControl1.Bearing = 0F;
this.gMapControl1.CanDragMap = true;
this.gMapControl1.ContextMenuStrip = this.contextMenuStrip1;
resources.ApplyResources(this.gMapControl1, "gMapControl1");
this.gMapControl1.GrayScaleMode = false;
this.gMapControl1.LevelsKeepInMemmory = 5;
this.gMapControl1.MarkersEnabled = true;
this.gMapControl1.MaxZoom = 2;
this.gMapControl1.MinZoom = 2;
this.gMapControl1.MouseWheelZoomType = GMap.NET.MouseWheelZoomType.MousePositionAndCenter;
this.gMapControl1.Name = "gMapControl1";
this.gMapControl1.NegativeMode = false;
this.gMapControl1.PolygonsEnabled = true;
this.gMapControl1.RetryLoadTile = 0;
this.gMapControl1.RoutesEnabled = true;
this.gMapControl1.ShowTileGridLines = false;
this.gMapControl1.streamjpg = ((System.IO.MemoryStream)(resources.GetObject("gMapControl1.streamjpg")));
this.gMapControl1.Zoom = 0D;
this.gMapControl1.Click += new System.EventHandler(this.gMapControl1_Click);
this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown);
this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove);
//
// panel1
//
this.panel1.Controls.Add(this.TXT_lat);
@ -1130,69 +1202,6 @@
this.CB_tuning.UseVisualStyleBackColor = true;
this.CB_tuning.CheckedChanged += new System.EventHandler(this.CB_tuning_CheckedChanged);
//
// panel2
//
this.panel2.Controls.Add(this.lbl_windvel);
this.panel2.Controls.Add(this.lbl_winddir);
this.panel2.Controls.Add(this.gMapControl1);
this.panel2.Controls.Add(this.zg1);
resources.ApplyResources(this.panel2, "panel2");
this.panel2.Name = "panel2";
//
// lbl_windvel
//
this.lbl_windvel.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_vel", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Vel: 0"));
resources.ApplyResources(this.lbl_windvel, "lbl_windvel");
this.lbl_windvel.Name = "lbl_windvel";
this.lbl_windvel.resize = true;
this.toolTip1.SetToolTip(this.lbl_windvel, resources.GetString("lbl_windvel.ToolTip"));
//
// lbl_winddir
//
this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0"));
resources.ApplyResources(this.lbl_winddir, "lbl_winddir");
this.lbl_winddir.Name = "lbl_winddir";
this.lbl_winddir.resize = true;
this.toolTip1.SetToolTip(this.lbl_winddir, resources.GetString("lbl_winddir.ToolTip"));
//
// gMapControl1
//
this.gMapControl1.BackColor = System.Drawing.Color.Transparent;
this.gMapControl1.Bearing = 0F;
this.gMapControl1.CanDragMap = true;
this.gMapControl1.ContextMenuStrip = this.contextMenuStrip1;
resources.ApplyResources(this.gMapControl1, "gMapControl1");
this.gMapControl1.GrayScaleMode = false;
this.gMapControl1.LevelsKeepInMemmory = 5;
this.gMapControl1.MarkersEnabled = true;
this.gMapControl1.MaxZoom = 2;
this.gMapControl1.MinZoom = 2;
this.gMapControl1.MouseWheelZoomType = GMap.NET.MouseWheelZoomType.MousePositionAndCenter;
this.gMapControl1.Name = "gMapControl1";
this.gMapControl1.NegativeMode = false;
this.gMapControl1.PolygonsEnabled = true;
this.gMapControl1.RetryLoadTile = 0;
this.gMapControl1.RoutesEnabled = true;
this.gMapControl1.ShowTileGridLines = false;
this.gMapControl1.streamjpg = ((System.IO.MemoryStream)(resources.GetObject("gMapControl1.streamjpg")));
this.gMapControl1.Zoom = 0D;
this.gMapControl1.Click += new System.EventHandler(this.gMapControl1_Click);
this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown);
this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove);
//
// zg1
//
resources.ApplyResources(this.zg1, "zg1");
this.zg1.Name = "zg1";
this.zg1.ScrollGrace = 0D;
this.zg1.ScrollMaxX = 0D;
this.zg1.ScrollMaxY = 0D;
this.zg1.ScrollMaxY2 = 0D;
this.zg1.ScrollMinX = 0D;
this.zg1.ScrollMinY = 0D;
this.zg1.ScrollMinY2 = 0D;
this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick);
//
// dataGridViewImageColumn1
//
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
@ -1254,10 +1263,12 @@
((System.ComponentModel.ISupportInitialize)(this.NUM_playbackspeed)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.tracklog)).EndInit();
this.tableMap.ResumeLayout(false);
this.splitContainer1.Panel1.ResumeLayout(false);
this.splitContainer1.Panel2.ResumeLayout(false);
this.splitContainer1.ResumeLayout(false);
this.panel1.ResumeLayout(false);
this.panel1.PerformLayout();
((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).EndInit();
this.panel2.ResumeLayout(false);
this.ResumeLayout(false);
}
@ -1294,7 +1305,6 @@
private ArdupilotMega.MyLabel TXT_long;
private ArdupilotMega.MyLabel TXT_alt;
private System.Windows.Forms.CheckBox CHK_autopan;
private System.Windows.Forms.Panel panel2;
private GMap.NET.WindowsForms.GMapControl gMapControl1;
private ZedGraph.ZedGraphControl zg1;
private System.Windows.Forms.TabControl tabControl1;
@ -1320,5 +1330,6 @@
private System.Windows.Forms.ToolStripMenuItem stopRecordToolStripMenuItem;
private MyLabel lbl_logpercent;
private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem;
private System.Windows.Forms.SplitContainer splitContainer1;
}
}

View File

@ -31,18 +31,33 @@ namespace ArdupilotMega.GCSViews
RollingPointPairList list3 = new RollingPointPairList(1200);
RollingPointPairList list4 = new RollingPointPairList(1200);
RollingPointPairList list5 = new RollingPointPairList(1200);
RollingPointPairList list6 = new RollingPointPairList(1200);
RollingPointPairList list7 = new RollingPointPairList(1200);
RollingPointPairList list8 = new RollingPointPairList(1200);
RollingPointPairList list9 = new RollingPointPairList(1200);
RollingPointPairList list10 = new RollingPointPairList(1200);
System.Reflection.PropertyInfo list1item = null;
System.Reflection.PropertyInfo list2item = null;
System.Reflection.PropertyInfo list3item = null;
System.Reflection.PropertyInfo list4item = null;
System.Reflection.PropertyInfo list5item = null;
System.Reflection.PropertyInfo list6item = null;
System.Reflection.PropertyInfo list7item = null;
System.Reflection.PropertyInfo list8item = null;
System.Reflection.PropertyInfo list9item = null;
System.Reflection.PropertyInfo list10item = null;
CurveItem list1curve;
CurveItem list2curve;
CurveItem list3curve;
CurveItem list4curve;
CurveItem list5curve;
CurveItem list6curve;
CurveItem list7curve;
CurveItem list8curve;
CurveItem list9curve;
CurveItem list10curve;
bool huddropout = false;
bool huddropoutresize = false;
@ -77,10 +92,22 @@ namespace ArdupilotMega.GCSViews
Control.CheckForIllegalCrossThreadCalls = false; // so can update display from another thread
// setup default tuning graph
chk_box_CheckedChanged((object)(new CheckBox() { Name = "roll", Checked = true }), new EventArgs());
chk_box_CheckedChanged((object)(new CheckBox() { Name = "pitch", Checked = true }), new EventArgs());
chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_roll", Checked = true }), new EventArgs());
chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_pitch", Checked = true }), new EventArgs());
if (MainV2.config["Tuning_Graph_Selected"] != null)
{
string line = MainV2.config["Tuning_Graph_Selected"].ToString();
string[] lines = line.Split(new char[] { '|' }, StringSplitOptions.RemoveEmptyEntries);
foreach (string option in lines)
{
chk_box_CheckedChanged((object)(new CheckBox() { Name = option, Checked = true }), new EventArgs());
}
}
else
{
chk_box_CheckedChanged((object)(new CheckBox() { Name = "roll", Checked = true }), new EventArgs());
chk_box_CheckedChanged((object)(new CheckBox() { Name = "pitch", Checked = true }), new EventArgs());
chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_roll", Checked = true }), new EventArgs());
chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_pitch", Checked = true }), new EventArgs());
}
List<string> list = new List<string>();
@ -314,6 +341,16 @@ namespace ArdupilotMega.GCSViews
list4.Add(time, (float)list4item.GetValue((object)MainV2.cs, null));
if (list5item != null)
list5.Add(time, (float)list5item.GetValue((object)MainV2.cs, null));
if (list6item != null)
list6.Add(time, (float)list6item.GetValue((object)MainV2.cs, null));
if (list7item != null)
list7.Add(time, (float)list7item.GetValue((object)MainV2.cs, null));
if (list8item != null)
list8.Add(time, (float)list8item.GetValue((object)MainV2.cs, null));
if (list9item != null)
list9.Add(time, (float)list9item.GetValue((object)MainV2.cs, null));
if (list10item != null)
list10.Add(time, (float)list10item.GetValue((object)MainV2.cs, null));
}
if (tracklast.AddSeconds(1) < DateTime.Now)
@ -681,14 +718,14 @@ namespace ArdupilotMega.GCSViews
{
if (CB_tuning.Checked)
{
gMapControl1.Visible = false;
splitContainer1.Panel1Collapsed = false;
ZedGraphTimer.Enabled = true;
ZedGraphTimer.Start();
zg1.Visible = true;
}
else
{
gMapControl1.Visible = true;
splitContainer1.Panel1Collapsed = true;
ZedGraphTimer.Enabled = false;
ZedGraphTimer.Stop();
zg1.Visible = false;
@ -1203,6 +1240,8 @@ namespace ArdupilotMega.GCSViews
return;
}
}
}
private void zg1_DoubleClick(object sender, EventArgs e)
@ -1210,7 +1249,7 @@ namespace ArdupilotMega.GCSViews
Form selectform = new Form()
{
Name = "select",
Width = 650,
Width = 750,
Height = 250,
Text = "Graph This"
};
@ -1218,6 +1257,19 @@ namespace ArdupilotMega.GCSViews
int x = 10;
int y = 10;
{
CheckBox chk_box = new CheckBox();
chk_box.Text = "Logarithmic";
chk_box.Name = "Logarithmic";
chk_box.Location = new Point(x, y);
chk_box.Size = new System.Drawing.Size(100, 20);
chk_box.CheckedChanged += new EventHandler(chk_log_CheckedChanged);
selectform.Controls.Add(chk_box);
}
y += 20;
object thisBoxed = MainV2.cs;
Type test = thisBoxed.GetType();
@ -1249,6 +1301,16 @@ namespace ArdupilotMega.GCSViews
chk_box.Checked = true;
if (list5item != null && list5item.Name == field.Name)
chk_box.Checked = true;
if (list6item != null && list6item.Name == field.Name)
chk_box.Checked = true;
if (list7item != null && list7item.Name == field.Name)
chk_box.Checked = true;
if (list8item != null && list8item.Name == field.Name)
chk_box.Checked = true;
if (list9item != null && list9item.Name == field.Name)
chk_box.Checked = true;
if (list10item != null && list10item.Name == field.Name)
chk_box.Checked = true;
chk_box.Text = field.Name;
chk_box.Name = field.Name;
@ -1273,6 +1335,18 @@ namespace ArdupilotMega.GCSViews
selectform.Show();
}
void chk_log_CheckedChanged(object sender, EventArgs e)
{
if (((CheckBox)sender).Checked)
{
zg1.GraphPane.YAxis.Type = AxisType.Log;
}
else
{
zg1.GraphPane.YAxis.Type = AxisType.Linear;
}
}
void chk_box_CheckedChanged(object sender, EventArgs e)
{
if (((CheckBox)sender).Checked)
@ -1302,12 +1376,55 @@ namespace ArdupilotMega.GCSViews
setupPropertyInfo(ref list5item, ((CheckBox)sender).Name, MainV2.cs);
list5curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list5, Color.Yellow, SymbolType.None);
}
else if (list6item == null)
{
setupPropertyInfo(ref list6item, ((CheckBox)sender).Name, MainV2.cs);
list6curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list6, Color.Magenta, SymbolType.None);
}
else if (list7item == null)
{
setupPropertyInfo(ref list7item, ((CheckBox)sender).Name, MainV2.cs);
list7curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list7, Color.Purple, SymbolType.None);
}
else if (list8item == null)
{
setupPropertyInfo(ref list8item, ((CheckBox)sender).Name, MainV2.cs);
list8curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list8, Color.LimeGreen, SymbolType.None);
}
else if (list9item == null)
{
setupPropertyInfo(ref list9item, ((CheckBox)sender).Name, MainV2.cs);
list9curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list9, Color.Cyan, SymbolType.None);
}
else if (list10item == null)
{
setupPropertyInfo(ref list10item, ((CheckBox)sender).Name, MainV2.cs);
list10curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list10, Color.Violet, SymbolType.None);
}
else
{
MessageBox.Show("Max 5 at a time.");
MessageBox.Show("Max 10 at a time.");
((CheckBox)sender).Checked = false;
}
MainV2.fixtheme(this);
string selected = "";
try
{
selected = selected + zg1.GraphPane.CurveList[0].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[1].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[2].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[3].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[4].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[5].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[6].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[7].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[8].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[9].Label.Text + "|";
selected = selected + zg1.GraphPane.CurveList[10].Label.Text + "|";
}
catch { }
MainV2.config["Tuning_Graph_Selected"] = selected;
}
else
{
@ -1336,6 +1453,31 @@ namespace ArdupilotMega.GCSViews
{
list5item = null;
zg1.GraphPane.CurveList.Remove(list5curve);
}
if (list6item != null && list6item.Name == ((CheckBox)sender).Name)
{
list6item = null;
zg1.GraphPane.CurveList.Remove(list6curve);
}
if (list7item != null && list7item.Name == ((CheckBox)sender).Name)
{
list7item = null;
zg1.GraphPane.CurveList.Remove(list7curve);
}
if (list8item != null && list8item.Name == ((CheckBox)sender).Name)
{
list8item = null;
zg1.GraphPane.CurveList.Remove(list8curve);
}
if (list9item != null && list9item.Name == ((CheckBox)sender).Name)
{
list9item = null;
zg1.GraphPane.CurveList.Remove(list9curve);
}
if (list10item != null && list10item.Name == ((CheckBox)sender).Name)
{
list10item = null;
zg1.GraphPane.CurveList.Remove(list10curve);
}
}
}

View File

@ -134,7 +134,7 @@
<value>Point Camera Here</value>
</data>
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
<value>175, 70</value>
<value>175, 48</value>
</data>
<data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve">
<value>contextMenuStrip1</value>
@ -1083,290 +1083,68 @@
<data name="MainH.Panel1MinSize" type="System.Int32, mscorlib">
<value>360</value>
</data>
<data name="tableMap.CellBorderStyle" type="System.Windows.Forms.TableLayoutPanelCellBorderStyle, System.Windows.Forms">
<value>Single</value>
</data>
<data name="tableMap.ColumnCount" type="System.Int32, mscorlib">
<value>1</value>
</data>
<data name="TXT_lat.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_lat.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_lat.Location" type="System.Drawing.Point, System.Drawing">
<value>10, 10</value>
</data>
<data name="TXT_lat.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_lat.TabIndex" type="System.Int32, mscorlib">
<value>13</value>
</data>
<data name="TXT_lat.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_lat.Name" xml:space="preserve">
<value>TXT_lat</value>
</data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_lat.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="Zoomlevel.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="Zoomlevel.Location" type="System.Drawing.Point, System.Drawing">
<value>438, 7</value>
</data>
<data name="Zoomlevel.Size" type="System.Drawing.Size, System.Drawing">
<value>76, 20</value>
</data>
<data name="Zoomlevel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="Zoomlevel.ToolTip" xml:space="preserve">
<value>Change Zoom Level</value>
</data>
<data name="&gt;&gt;Zoomlevel.Name" xml:space="preserve">
<value>Zoomlevel</value>
</data>
<data name="&gt;&gt;Zoomlevel.Type" xml:space="preserve">
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;Zoomlevel.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;Zoomlevel.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="label1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="label1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>401, 10</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label1.TabIndex" type="System.Int32, mscorlib">
<value>70</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>Zoom</value>
</data>
<data name="&gt;&gt;label1.Name" xml:space="preserve">
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="TXT_long.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_long.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_long.Location" type="System.Drawing.Point, System.Drawing">
<value>100, 10</value>
</data>
<data name="TXT_long.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_long.TabIndex" type="System.Int32, mscorlib">
<value>14</value>
</data>
<data name="TXT_long.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_long.Name" xml:space="preserve">
<value>TXT_long</value>
</data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_long.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="TXT_alt.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_alt.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_alt.Location" type="System.Drawing.Point, System.Drawing">
<value>190, 10</value>
</data>
<data name="TXT_alt.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="TXT_alt.TabIndex" type="System.Int32, mscorlib">
<value>15</value>
</data>
<data name="TXT_alt.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_alt.Name" xml:space="preserve">
<value>TXT_alt</value>
</data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_alt.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="CHK_autopan.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CHK_autopan.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_autopan.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_autopan.Location" type="System.Drawing.Point, System.Drawing">
<value>325, 10</value>
</data>
<data name="CHK_autopan.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 17</value>
</data>
<data name="CHK_autopan.TabIndex" type="System.Int32, mscorlib">
<value>68</value>
</data>
<data name="CHK_autopan.Text" xml:space="preserve">
<value>Auto Pan</value>
</data>
<data name="CHK_autopan.ToolTip" xml:space="preserve">
<value>Makes the map autopan based on current location</value>
</data>
<data name="&gt;&gt;CHK_autopan.Name" xml:space="preserve">
<value>CHK_autopan</value>
</data>
<data name="&gt;&gt;CHK_autopan.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_autopan.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CHK_autopan.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="CB_tuning.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CB_tuning.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CB_tuning.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CB_tuning.Location" type="System.Drawing.Point, System.Drawing">
<value>260, 9</value>
</data>
<data name="CB_tuning.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="CB_tuning.TabIndex" type="System.Int32, mscorlib">
<value>62</value>
</data>
<data name="CB_tuning.Text" xml:space="preserve">
<value>Tuning</value>
</data>
<data name="CB_tuning.ToolTip" xml:space="preserve">
<value>Show the tunning graph, chowing target attitudes vs actual</value>
</data>
<data name="&gt;&gt;CB_tuning.Name" xml:space="preserve">
<value>CB_tuning</value>
</data>
<data name="&gt;&gt;CB_tuning.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CB_tuning.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CB_tuning.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="panel1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<data name="splitContainer1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel1.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 429</value>
<data name="splitContainer1.Location" type="System.Drawing.Point, System.Drawing">
<value>4, 4</value>
</data>
<data name="panel1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
<data name="splitContainer1.Orientation" type="System.Windows.Forms.Orientation, System.Windows.Forms">
<value>Horizontal</value>
</data>
<data name="panel1.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 30</value>
<data name="zg1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel1.TabIndex" type="System.Int32, mscorlib">
<data name="zg1.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
</data>
<data name="zg1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>4, 4, 4, 4</value>
</data>
<data name="zg1.Size" type="System.Drawing.Size, System.Drawing">
<value>577, 210</value>
</data>
<data name="zg1.TabIndex" type="System.Int32, mscorlib">
<value>67</value>
</data>
<data name="zg1.Visible" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="&gt;&gt;zg1.Name" xml:space="preserve">
<value>zg1</value>
</data>
<data name="&gt;&gt;zg1.Type" xml:space="preserve">
<value>ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60</value>
</data>
<data name="&gt;&gt;zg1.Parent" xml:space="preserve">
<value>splitContainer1.Panel1</value>
</data>
<data name="&gt;&gt;zg1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;panel1.Name" xml:space="preserve">
<value>panel1</value>
<data name="&gt;&gt;splitContainer1.Panel1.Name" xml:space="preserve">
<value>splitContainer1.Panel1</value>
</data>
<data name="&gt;&gt;panel1.Type" xml:space="preserve">
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
<data name="&gt;&gt;splitContainer1.Panel1.Type" xml:space="preserve">
<value>System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;panel1.Parent" xml:space="preserve">
<value>tableMap</value>
<data name="&gt;&gt;splitContainer1.Panel1.Parent" xml:space="preserve">
<value>splitContainer1</value>
</data>
<data name="&gt;&gt;panel1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_windvel.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_windvel.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 21</value>
</data>
<data name="lbl_windvel.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="lbl_windvel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="lbl_windvel.Text" xml:space="preserve">
<value>Vel: 0</value>
</data>
<data name="lbl_windvel.ToolTip" xml:space="preserve">
<value>Estimated Wind Velocity</value>
</data>
<data name="&gt;&gt;lbl_windvel.Name" xml:space="preserve">
<value>lbl_windvel</value>
</data>
<data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
<value>panel2</value>
</data>
<data name="&gt;&gt;lbl_windvel.ZOrder" xml:space="preserve">
<data name="&gt;&gt;splitContainer1.Panel1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_winddir.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_winddir.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 8</value>
<value>4, 7</value>
</data>
<data name="lbl_winddir.Size" type="System.Drawing.Size, System.Drawing">
<value>32, 13</value>
@ -1387,9 +1165,39 @@
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;lbl_winddir.Parent" xml:space="preserve">
<value>panel2</value>
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_winddir.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_windvel.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_windvel.Location" type="System.Drawing.Point, System.Drawing">
<value>4, 20</value>
</data>
<data name="lbl_windvel.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="lbl_windvel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="lbl_windvel.Text" xml:space="preserve">
<value>Vel: 0</value>
</data>
<data name="lbl_windvel.ToolTip" xml:space="preserve">
<value>Estimated Wind Velocity</value>
</data>
<data name="&gt;&gt;lbl_windvel.Name" xml:space="preserve">
<value>lbl_windvel</value>
</data>
<data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_windvel.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="gMapControl1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
@ -1402,7 +1210,7 @@
<value>0, 0, 0, 0</value>
</data>
<data name="gMapControl1.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 429</value>
<value>577, 420</value>
</data>
<data name="gMapControl1.streamjpg" mimetype="application/x-microsoft.net.object.binary.base64">
<value>
@ -1559,66 +1367,288 @@
<value>GMap.NET.WindowsForms.GMapControl, GMap.NET.WindowsForms, Version=1.5.5.5, Culture=neutral, PublicKeyToken=b85b9027b614afef</value>
</data>
<data name="&gt;&gt;gMapControl1.Parent" xml:space="preserve">
<value>panel2</value>
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;gMapControl1.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="zg1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
<data name="&gt;&gt;splitContainer1.Panel2.Name" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="zg1.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
<data name="&gt;&gt;splitContainer1.Panel2.Type" xml:space="preserve">
<value>System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="zg1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>4, 4, 4, 4</value>
<data name="&gt;&gt;splitContainer1.Panel2.Parent" xml:space="preserve">
<value>splitContainer1</value>
</data>
<data name="zg1.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 429</value>
</data>
<data name="zg1.TabIndex" type="System.Int32, mscorlib">
<value>67</value>
</data>
<data name="zg1.Visible" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="&gt;&gt;zg1.Name" xml:space="preserve">
<value>zg1</value>
</data>
<data name="&gt;&gt;zg1.Type" xml:space="preserve">
<value>ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60</value>
</data>
<data name="&gt;&gt;zg1.Parent" xml:space="preserve">
<value>panel2</value>
</data>
<data name="&gt;&gt;zg1.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="panel2.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel2.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
</data>
<data name="panel2.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
</data>
<data name="panel2.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 429</value>
</data>
<data name="panel2.TabIndex" type="System.Int32, mscorlib">
<data name="&gt;&gt;splitContainer1.Panel2.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="&gt;&gt;panel2.Name" xml:space="preserve">
<value>panel2</value>
<data name="splitContainer1.Size" type="System.Drawing.Size, System.Drawing">
<value>577, 420</value>
</data>
<data name="&gt;&gt;panel2.Type" xml:space="preserve">
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
<data name="splitContainer1.SplitterDistance" type="System.Int32, mscorlib">
<value>210</value>
</data>
<data name="&gt;&gt;panel2.Parent" xml:space="preserve">
<data name="splitContainer1.TabIndex" type="System.Int32, mscorlib">
<value>76</value>
</data>
<data name="&gt;&gt;splitContainer1.Name" xml:space="preserve">
<value>splitContainer1</value>
</data>
<data name="&gt;&gt;splitContainer1.Type" xml:space="preserve">
<value>System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;splitContainer1.Parent" xml:space="preserve">
<value>tableMap</value>
</data>
<data name="&gt;&gt;panel2.ZOrder" xml:space="preserve">
<data name="&gt;&gt;splitContainer1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="TXT_lat.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_lat.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_lat.Location" type="System.Drawing.Point, System.Drawing">
<value>10, 11</value>
</data>
<data name="TXT_lat.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_lat.TabIndex" type="System.Int32, mscorlib">
<value>13</value>
</data>
<data name="TXT_lat.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_lat.Name" xml:space="preserve">
<value>TXT_lat</value>
</data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_lat.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="Zoomlevel.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="Zoomlevel.Location" type="System.Drawing.Point, System.Drawing">
<value>438, 8</value>
</data>
<data name="Zoomlevel.Size" type="System.Drawing.Size, System.Drawing">
<value>76, 20</value>
</data>
<data name="Zoomlevel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="Zoomlevel.ToolTip" xml:space="preserve">
<value>Change Zoom Level</value>
</data>
<data name="&gt;&gt;Zoomlevel.Name" xml:space="preserve">
<value>Zoomlevel</value>
</data>
<data name="&gt;&gt;Zoomlevel.Type" xml:space="preserve">
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;Zoomlevel.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;Zoomlevel.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="label1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="label1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>401, 11</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label1.TabIndex" type="System.Int32, mscorlib">
<value>70</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>Zoom</value>
</data>
<data name="&gt;&gt;label1.Name" xml:space="preserve">
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="TXT_long.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_long.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_long.Location" type="System.Drawing.Point, System.Drawing">
<value>100, 11</value>
</data>
<data name="TXT_long.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_long.TabIndex" type="System.Int32, mscorlib">
<value>14</value>
</data>
<data name="TXT_long.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_long.Name" xml:space="preserve">
<value>TXT_long</value>
</data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_long.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="TXT_alt.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_alt.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_alt.Location" type="System.Drawing.Point, System.Drawing">
<value>190, 11</value>
</data>
<data name="TXT_alt.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="TXT_alt.TabIndex" type="System.Int32, mscorlib">
<value>15</value>
</data>
<data name="TXT_alt.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_alt.Name" xml:space="preserve">
<value>TXT_alt</value>
</data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_alt.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="CHK_autopan.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CHK_autopan.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_autopan.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_autopan.Location" type="System.Drawing.Point, System.Drawing">
<value>325, 11</value>
</data>
<data name="CHK_autopan.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 17</value>
</data>
<data name="CHK_autopan.TabIndex" type="System.Int32, mscorlib">
<value>68</value>
</data>
<data name="CHK_autopan.Text" xml:space="preserve">
<value>Auto Pan</value>
</data>
<data name="CHK_autopan.ToolTip" xml:space="preserve">
<value>Makes the map autopan based on current location</value>
</data>
<data name="&gt;&gt;CHK_autopan.Name" xml:space="preserve">
<value>CHK_autopan</value>
</data>
<data name="&gt;&gt;CHK_autopan.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_autopan.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CHK_autopan.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="CB_tuning.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CB_tuning.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CB_tuning.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CB_tuning.Location" type="System.Drawing.Point, System.Drawing">
<value>260, 10</value>
</data>
<data name="CB_tuning.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="CB_tuning.TabIndex" type="System.Int32, mscorlib">
<value>62</value>
</data>
<data name="CB_tuning.Text" xml:space="preserve">
<value>Tuning</value>
</data>
<data name="CB_tuning.ToolTip" xml:space="preserve">
<value>Show the tunning graph, chowing target attitudes vs actual</value>
</data>
<data name="&gt;&gt;CB_tuning.Name" xml:space="preserve">
<value>CB_tuning</value>
</data>
<data name="&gt;&gt;CB_tuning.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CB_tuning.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CB_tuning.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="panel1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel1.Location" type="System.Drawing.Point, System.Drawing">
<value>1, 428</value>
</data>
<data name="panel1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
</data>
<data name="panel1.Size" type="System.Drawing.Size, System.Drawing">
<value>583, 30</value>
</data>
<data name="panel1.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="&gt;&gt;panel1.Name" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;panel1.Type" xml:space="preserve">
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;panel1.Parent" xml:space="preserve">
<value>tableMap</value>
</data>
<data name="&gt;&gt;panel1.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="tableMap.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
@ -1649,7 +1679,7 @@
<value>0</value>
</data>
<data name="tableMap.LayoutSettings" type="System.Windows.Forms.TableLayoutSettings, System.Windows.Forms">
<value>&lt;?xml version="1.0" encoding="utf-16"?&gt;&lt;TableLayoutSettings&gt;&lt;Controls&gt;&lt;Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;Control Name="panel2" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;/Controls&gt;&lt;Columns Styles="Percent,100" /&gt;&lt;Rows Styles="Percent,100,Absolute,30" /&gt;&lt;/TableLayoutSettings&gt;</value>
<value>&lt;?xml version="1.0" encoding="utf-16"?&gt;&lt;TableLayoutSettings&gt;&lt;Controls&gt;&lt;Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;/Controls&gt;&lt;Columns Styles="Percent,100" /&gt;&lt;Rows Styles="Percent,100,Absolute,30,Absolute,20" /&gt;&lt;/TableLayoutSettings&gt;</value>
</data>
<data name="&gt;&gt;MainH.Panel2.Name" xml:space="preserve">
<value>MainH.Panel2</value>

View File

@ -277,7 +277,7 @@ namespace ArdupilotMega.GCSViews
cell = Commands.Rows[selectedrow].Cells[1] as DataGridViewTextBoxCell;
cell.Value = 0;
}
if (Commands.Columns[Param2.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][1]/*"Alt"*/))
if (alt != -1 && Commands.Columns[Param2.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][1]/*"Alt"*/))
{
cell = Commands.Rows[selectedrow].Cells[2] as DataGridViewTextBoxCell;
@ -1719,7 +1719,7 @@ namespace ArdupilotMega.GCSViews
}
else
{
callMeDrag(CurentRectMarker.InnerMarker.Tag.ToString(), currentMarker.Position.Lat, currentMarker.Position.Lng, 0);
callMeDrag(CurentRectMarker.InnerMarker.Tag.ToString(), currentMarker.Position.Lat, currentMarker.Position.Lng, -1);
}
CurentRectMarker = null;
}

View File

@ -47,7 +47,7 @@ namespace ArdupilotMega
self = this;
}
JoyChannel[] JoyChannels = new JoyChannel[5]; // we are base 1
JoyChannel[] JoyChannels = new JoyChannel[9]; // we are base 1
JoyButton[] JoyButtons = new JoyButton[128]; // base 0
public static DeviceList getDevices()
@ -301,16 +301,22 @@ namespace ArdupilotMega
ushort roll = pickchannel(1, JoyChannels[1].axis, false, JoyChannels[1].expo);
ushort pitch = pickchannel(2, JoyChannels[2].axis, false, JoyChannels[2].expo);
MainV2.cs.rcoverridech1 = (ushort)(BOOL_TO_SIGN(JoyChannels[1].reverse) * ((int)(pitch - 1500) - (int)(roll - 1500)) / 2 + 1500);
MainV2.cs.rcoverridech2 = (ushort)(BOOL_TO_SIGN(JoyChannels[2].reverse) * ((int)(pitch - 1500) + (int)(roll - 1500)) / 2 + 1500);
if (getJoystickAxis(1) != Joystick.joystickaxis.None)
MainV2.cs.rcoverridech1 = (ushort)(BOOL_TO_SIGN(JoyChannels[1].reverse) * ((int)(pitch - 1500) - (int)(roll - 1500)) / 2 + 1500);
if (getJoystickAxis(2) != Joystick.joystickaxis.None)
MainV2.cs.rcoverridech2 = (ushort)(BOOL_TO_SIGN(JoyChannels[2].reverse) * ((int)(pitch - 1500) + (int)(roll - 1500)) / 2 + 1500);
}
else
{
MainV2.cs.rcoverridech1 = pickchannel(1, JoyChannels[1].axis, JoyChannels[1].reverse, JoyChannels[1].expo);//(ushort)(((int)state.Rz / 65.535) + 1000);
MainV2.cs.rcoverridech2 = pickchannel(2, JoyChannels[2].axis, JoyChannels[2].reverse, JoyChannels[2].expo);//(ushort)(((int)state.Y / 65.535) + 1000);
if (getJoystickAxis(1) != Joystick.joystickaxis.None)
MainV2.cs.rcoverridech1 = pickchannel(1, JoyChannels[1].axis, JoyChannels[1].reverse, JoyChannels[1].expo);//(ushort)(((int)state.Rz / 65.535) + 1000);
if (getJoystickAxis(2) != Joystick.joystickaxis.None)
MainV2.cs.rcoverridech2 = pickchannel(2, JoyChannels[2].axis, JoyChannels[2].reverse, JoyChannels[2].expo);//(ushort)(((int)state.Y / 65.535) + 1000);
}
MainV2.cs.rcoverridech3 = pickchannel(3, JoyChannels[3].axis, JoyChannels[3].reverse, JoyChannels[3].expo);//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000);
MainV2.cs.rcoverridech4 = pickchannel(4, JoyChannels[4].axis, JoyChannels[4].reverse, JoyChannels[4].expo);//(ushort)(((int)state.X / 65.535) + 1000);
if (getJoystickAxis(3) != Joystick.joystickaxis.None)
MainV2.cs.rcoverridech3 = pickchannel(3, JoyChannels[3].axis, JoyChannels[3].reverse, JoyChannels[3].expo);//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000);
if (getJoystickAxis(4) != Joystick.joystickaxis.None)
MainV2.cs.rcoverridech4 = pickchannel(4, JoyChannels[4].axis, JoyChannels[4].reverse, JoyChannels[4].expo);//(ushort)(((int)state.X / 65.535) + 1000);
foreach (JoyButton but in JoyButtons)
{
@ -349,6 +355,7 @@ namespace ArdupilotMega
public enum joystickaxis
{
None,
Pass,
ARx,
ARy,
ARz,
@ -462,6 +469,15 @@ namespace ArdupilotMega
return joystick.Caps.NumberButtons;
}
public joystickaxis getJoystickAxis(int channel)
{
try
{
return JoyChannels[channel].axis;
}
catch { return joystickaxis.None; }
}
public bool isButtonPressed(int buttonno)
{
byte[] buts = state.GetButtons();
@ -510,6 +526,12 @@ namespace ArdupilotMega
switch (axis)
{
case joystickaxis.None:
working = ushort.MaxValue / 2;
break;
case joystickaxis.Pass:
working = (int)(((float)(trim - min) / range) * ushort.MaxValue);
break;
case joystickaxis.ARx:
working = state.ARx;
break;

View File

@ -53,6 +53,25 @@
this.label8 = new System.Windows.Forms.Label();
this.label9 = new System.Windows.Forms.Label();
this.timer1 = new System.Windows.Forms.Timer(this.components);
this.CHK_elevons = new System.Windows.Forms.CheckBox();
this.revCH5 = new System.Windows.Forms.CheckBox();
this.label10 = new System.Windows.Forms.Label();
this.expo_ch5 = new System.Windows.Forms.TextBox();
this.CMB_CH5 = new System.Windows.Forms.ComboBox();
this.revCH6 = new System.Windows.Forms.CheckBox();
this.label11 = new System.Windows.Forms.Label();
this.expo_ch6 = new System.Windows.Forms.TextBox();
this.CMB_CH6 = new System.Windows.Forms.ComboBox();
this.revCH7 = new System.Windows.Forms.CheckBox();
this.label12 = new System.Windows.Forms.Label();
this.expo_ch7 = new System.Windows.Forms.TextBox();
this.CMB_CH7 = new System.Windows.Forms.ComboBox();
this.revCH8 = new System.Windows.Forms.CheckBox();
this.label13 = new System.Windows.Forms.Label();
this.expo_ch8 = new System.Windows.Forms.TextBox();
this.CMB_CH8 = new System.Windows.Forms.ComboBox();
this.BUT_detch8 = new ArdupilotMega.MyButton();
this.horizontalProgressBar4 = new ArdupilotMega.HorizontalProgressBar();
this.BUT_detch4 = new ArdupilotMega.MyButton();
this.BUT_detch3 = new ArdupilotMega.MyButton();
this.BUT_detch2 = new ArdupilotMega.MyButton();
@ -63,7 +82,12 @@
this.progressBar3 = new ArdupilotMega.HorizontalProgressBar();
this.progressBar2 = new ArdupilotMega.HorizontalProgressBar();
this.progressBar1 = new ArdupilotMega.HorizontalProgressBar();
this.CHK_elevons = new System.Windows.Forms.CheckBox();
this.BUT_detch5 = new ArdupilotMega.MyButton();
this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar();
this.BUT_detch6 = new ArdupilotMega.MyButton();
this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar();
this.BUT_detch7 = new ArdupilotMega.MyButton();
this.horizontalProgressBar3 = new ArdupilotMega.HorizontalProgressBar();
this.SuspendLayout();
//
// CMB_joysticks
@ -224,6 +248,151 @@
this.timer1.Enabled = true;
this.timer1.Tick += new System.EventHandler(this.timer1_Tick);
//
// CHK_elevons
//
resources.ApplyResources(this.CHK_elevons, "CHK_elevons");
this.CHK_elevons.Name = "CHK_elevons";
this.CHK_elevons.UseVisualStyleBackColor = true;
this.CHK_elevons.CheckedChanged += new System.EventHandler(this.CHK_elevons_CheckedChanged);
//
// revCH5
//
resources.ApplyResources(this.revCH5, "revCH5");
this.revCH5.Name = "revCH5";
this.revCH5.UseVisualStyleBackColor = true;
this.revCH5.CheckedChanged += new System.EventHandler(this.revCH5_CheckedChanged);
//
// label10
//
resources.ApplyResources(this.label10, "label10");
this.label10.Name = "label10";
//
// expo_ch5
//
this.expo_ch5.BorderStyle = System.Windows.Forms.BorderStyle.None;
resources.ApplyResources(this.expo_ch5, "expo_ch5");
this.expo_ch5.Name = "expo_ch5";
//
// CMB_CH5
//
this.CMB_CH5.FormattingEnabled = true;
this.CMB_CH5.Items.AddRange(new object[] {
resources.GetString("CMB_CH5.Items"),
resources.GetString("CMB_CH5.Items1"),
resources.GetString("CMB_CH5.Items2"),
resources.GetString("CMB_CH5.Items3")});
resources.ApplyResources(this.CMB_CH5, "CMB_CH5");
this.CMB_CH5.Name = "CMB_CH5";
this.CMB_CH5.SelectedIndexChanged += new System.EventHandler(this.CMB_CH5_SelectedIndexChanged);
//
// revCH6
//
resources.ApplyResources(this.revCH6, "revCH6");
this.revCH6.Name = "revCH6";
this.revCH6.UseVisualStyleBackColor = true;
this.revCH6.CheckedChanged += new System.EventHandler(this.revCH6_CheckedChanged);
//
// label11
//
resources.ApplyResources(this.label11, "label11");
this.label11.Name = "label11";
//
// expo_ch6
//
this.expo_ch6.BorderStyle = System.Windows.Forms.BorderStyle.None;
resources.ApplyResources(this.expo_ch6, "expo_ch6");
this.expo_ch6.Name = "expo_ch6";
//
// CMB_CH6
//
this.CMB_CH6.FormattingEnabled = true;
this.CMB_CH6.Items.AddRange(new object[] {
resources.GetString("CMB_CH6.Items"),
resources.GetString("CMB_CH6.Items1"),
resources.GetString("CMB_CH6.Items2"),
resources.GetString("CMB_CH6.Items3")});
resources.ApplyResources(this.CMB_CH6, "CMB_CH6");
this.CMB_CH6.Name = "CMB_CH6";
this.CMB_CH6.SelectedIndexChanged += new System.EventHandler(this.CMB_CH6_SelectedIndexChanged);
//
// revCH7
//
resources.ApplyResources(this.revCH7, "revCH7");
this.revCH7.Name = "revCH7";
this.revCH7.UseVisualStyleBackColor = true;
this.revCH7.CheckedChanged += new System.EventHandler(this.revCH7_CheckedChanged);
//
// label12
//
resources.ApplyResources(this.label12, "label12");
this.label12.Name = "label12";
//
// expo_ch7
//
this.expo_ch7.BorderStyle = System.Windows.Forms.BorderStyle.None;
resources.ApplyResources(this.expo_ch7, "expo_ch7");
this.expo_ch7.Name = "expo_ch7";
//
// CMB_CH7
//
this.CMB_CH7.FormattingEnabled = true;
this.CMB_CH7.Items.AddRange(new object[] {
resources.GetString("CMB_CH7.Items"),
resources.GetString("CMB_CH7.Items1"),
resources.GetString("CMB_CH7.Items2"),
resources.GetString("CMB_CH7.Items3")});
resources.ApplyResources(this.CMB_CH7, "CMB_CH7");
this.CMB_CH7.Name = "CMB_CH7";
this.CMB_CH7.SelectedIndexChanged += new System.EventHandler(this.CMB_CH7_SelectedIndexChanged);
//
// revCH8
//
resources.ApplyResources(this.revCH8, "revCH8");
this.revCH8.Name = "revCH8";
this.revCH8.UseVisualStyleBackColor = true;
this.revCH8.CheckedChanged += new System.EventHandler(this.revCH8_CheckedChanged);
//
// label13
//
resources.ApplyResources(this.label13, "label13");
this.label13.Name = "label13";
//
// expo_ch8
//
this.expo_ch8.BorderStyle = System.Windows.Forms.BorderStyle.None;
resources.ApplyResources(this.expo_ch8, "expo_ch8");
this.expo_ch8.Name = "expo_ch8";
//
// CMB_CH8
//
this.CMB_CH8.FormattingEnabled = true;
this.CMB_CH8.Items.AddRange(new object[] {
resources.GetString("CMB_CH8.Items"),
resources.GetString("CMB_CH8.Items1"),
resources.GetString("CMB_CH8.Items2"),
resources.GetString("CMB_CH8.Items3")});
resources.ApplyResources(this.CMB_CH8, "CMB_CH8");
this.CMB_CH8.Name = "CMB_CH8";
this.CMB_CH8.SelectedIndexChanged += new System.EventHandler(this.CMB_CH8_SelectedIndexChanged);
//
// BUT_detch8
//
resources.ApplyResources(this.BUT_detch8, "BUT_detch8");
this.BUT_detch8.Name = "BUT_detch8";
this.BUT_detch8.UseVisualStyleBackColor = true;
this.BUT_detch8.Click += new System.EventHandler(this.BUT_detch8_Click);
//
// horizontalProgressBar4
//
resources.ApplyResources(this.horizontalProgressBar4, "horizontalProgressBar4");
this.horizontalProgressBar4.Label = null;
this.horizontalProgressBar4.Maximum = 2200;
this.horizontalProgressBar4.maxline = 0;
this.horizontalProgressBar4.Minimum = 800;
this.horizontalProgressBar4.minline = 0;
this.horizontalProgressBar4.Name = "horizontalProgressBar4";
this.horizontalProgressBar4.Value = 800;
//
// BUT_detch4
//
resources.ApplyResources(this.BUT_detch4, "BUT_detch4");
@ -310,17 +479,88 @@
this.progressBar1.Name = "progressBar1";
this.progressBar1.Value = 800;
//
// CHK_elevons
// BUT_detch5
//
resources.ApplyResources(this.CHK_elevons, "CHK_elevons");
this.CHK_elevons.Name = "CHK_elevons";
this.CHK_elevons.UseVisualStyleBackColor = true;
this.CHK_elevons.CheckedChanged += new System.EventHandler(this.CHK_elevons_CheckedChanged);
resources.ApplyResources(this.BUT_detch5, "BUT_detch5");
this.BUT_detch5.Name = "BUT_detch5";
this.BUT_detch5.UseVisualStyleBackColor = true;
this.BUT_detch5.Click += new System.EventHandler(this.BUT_detch5_Click);
//
// horizontalProgressBar1
//
resources.ApplyResources(this.horizontalProgressBar1, "horizontalProgressBar1");
this.horizontalProgressBar1.Label = null;
this.horizontalProgressBar1.Maximum = 2200;
this.horizontalProgressBar1.maxline = 0;
this.horizontalProgressBar1.Minimum = 800;
this.horizontalProgressBar1.minline = 0;
this.horizontalProgressBar1.Name = "horizontalProgressBar1";
this.horizontalProgressBar1.Value = 800;
//
// BUT_detch6
//
resources.ApplyResources(this.BUT_detch6, "BUT_detch6");
this.BUT_detch6.Name = "BUT_detch6";
this.BUT_detch6.UseVisualStyleBackColor = true;
this.BUT_detch6.Click += new System.EventHandler(this.BUT_detch6_Click);
//
// horizontalProgressBar2
//
resources.ApplyResources(this.horizontalProgressBar2, "horizontalProgressBar2");
this.horizontalProgressBar2.Label = null;
this.horizontalProgressBar2.Maximum = 2200;
this.horizontalProgressBar2.maxline = 0;
this.horizontalProgressBar2.Minimum = 800;
this.horizontalProgressBar2.minline = 0;
this.horizontalProgressBar2.Name = "horizontalProgressBar2";
this.horizontalProgressBar2.Value = 800;
//
// BUT_detch7
//
resources.ApplyResources(this.BUT_detch7, "BUT_detch7");
this.BUT_detch7.Name = "BUT_detch7";
this.BUT_detch7.UseVisualStyleBackColor = true;
this.BUT_detch7.Click += new System.EventHandler(this.BUT_detch7_Click);
//
// horizontalProgressBar3
//
resources.ApplyResources(this.horizontalProgressBar3, "horizontalProgressBar3");
this.horizontalProgressBar3.Label = null;
this.horizontalProgressBar3.Maximum = 2200;
this.horizontalProgressBar3.maxline = 0;
this.horizontalProgressBar3.Minimum = 800;
this.horizontalProgressBar3.minline = 0;
this.horizontalProgressBar3.Name = "horizontalProgressBar3";
this.horizontalProgressBar3.Value = 800;
//
// JoystickSetup
//
resources.ApplyResources(this, "$this");
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.BUT_detch8);
this.Controls.Add(this.revCH8);
this.Controls.Add(this.label13);
this.Controls.Add(this.expo_ch8);
this.Controls.Add(this.horizontalProgressBar4);
this.Controls.Add(this.CMB_CH8);
this.Controls.Add(this.BUT_detch7);
this.Controls.Add(this.revCH7);
this.Controls.Add(this.label12);
this.Controls.Add(this.expo_ch7);
this.Controls.Add(this.horizontalProgressBar3);
this.Controls.Add(this.CMB_CH7);
this.Controls.Add(this.BUT_detch6);
this.Controls.Add(this.revCH6);
this.Controls.Add(this.label11);
this.Controls.Add(this.expo_ch6);
this.Controls.Add(this.horizontalProgressBar2);
this.Controls.Add(this.CMB_CH6);
this.Controls.Add(this.BUT_detch5);
this.Controls.Add(this.revCH5);
this.Controls.Add(this.label10);
this.Controls.Add(this.expo_ch5);
this.Controls.Add(this.horizontalProgressBar1);
this.Controls.Add(this.CMB_CH5);
this.Controls.Add(this.CHK_elevons);
this.Controls.Add(this.BUT_detch4);
this.Controls.Add(this.BUT_detch3);
@ -398,5 +638,29 @@
private MyButton BUT_detch3;
private MyButton BUT_detch4;
private System.Windows.Forms.CheckBox CHK_elevons;
private MyButton BUT_detch5;
private System.Windows.Forms.CheckBox revCH5;
private System.Windows.Forms.Label label10;
private System.Windows.Forms.TextBox expo_ch5;
private HorizontalProgressBar horizontalProgressBar1;
private System.Windows.Forms.ComboBox CMB_CH5;
private MyButton BUT_detch6;
private System.Windows.Forms.CheckBox revCH6;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.TextBox expo_ch6;
private HorizontalProgressBar horizontalProgressBar2;
private System.Windows.Forms.ComboBox CMB_CH6;
private MyButton BUT_detch7;
private System.Windows.Forms.CheckBox revCH7;
private System.Windows.Forms.Label label12;
private System.Windows.Forms.TextBox expo_ch7;
private HorizontalProgressBar horizontalProgressBar3;
private System.Windows.Forms.ComboBox CMB_CH7;
private MyButton BUT_detch8;
private System.Windows.Forms.CheckBox revCH8;
private System.Windows.Forms.Label label13;
private System.Windows.Forms.TextBox expo_ch8;
private HorizontalProgressBar horizontalProgressBar4;
private System.Windows.Forms.ComboBox CMB_CH8;
}
}

View File

@ -43,6 +43,10 @@ namespace ArdupilotMega
CMB_CH2.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis)));
CMB_CH3.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis)));
CMB_CH4.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis)));
CMB_CH5.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis)));
CMB_CH6.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis)));
CMB_CH7.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis)));
CMB_CH8.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis)));
try
{
@ -51,18 +55,30 @@ namespace ArdupilotMega
CMB_CH2.Text = MainV2.config["CMB_CH2"].ToString();
CMB_CH3.Text = MainV2.config["CMB_CH3"].ToString();
CMB_CH4.Text = MainV2.config["CMB_CH4"].ToString();
CMB_CH5.Text = MainV2.config["CMB_CH5"].ToString();
CMB_CH6.Text = MainV2.config["CMB_CH6"].ToString();
CMB_CH7.Text = MainV2.config["CMB_CH7"].ToString();
CMB_CH8.Text = MainV2.config["CMB_CH8"].ToString();
//revCH1
revCH1.Checked = bool.Parse(MainV2.config["revCH1"].ToString());
revCH2.Checked = bool.Parse(MainV2.config["revCH2"].ToString());
revCH3.Checked = bool.Parse(MainV2.config["revCH3"].ToString());
revCH4.Checked = bool.Parse(MainV2.config["revCH4"].ToString());
revCH5.Checked = bool.Parse(MainV2.config["revCH5"].ToString());
revCH6.Checked = bool.Parse(MainV2.config["revCH6"].ToString());
revCH7.Checked = bool.Parse(MainV2.config["revCH7"].ToString());
revCH8.Checked = bool.Parse(MainV2.config["revCH8"].ToString());
//expo_ch1
expo_ch1.Text = MainV2.config["expo_ch1"].ToString();
expo_ch2.Text = MainV2.config["expo_ch2"].ToString();
expo_ch3.Text = MainV2.config["expo_ch3"].ToString();
expo_ch4.Text = MainV2.config["expo_ch4"].ToString();
expo_ch5.Text = MainV2.config["expo_ch5"].ToString();
expo_ch6.Text = MainV2.config["expo_ch6"].ToString();
expo_ch7.Text = MainV2.config["expo_ch7"].ToString();
expo_ch8.Text = MainV2.config["expo_ch8"].ToString();
CHK_elevons.Checked = bool.Parse(MainV2.config["joy_elevons"].ToString());
}
@ -104,6 +120,10 @@ namespace ArdupilotMega
joy.setChannel(2, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH2.Text), revCH2.Checked, int.Parse(expo_ch2.Text));
joy.setChannel(3, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH3.Text), revCH3.Checked, int.Parse(expo_ch3.Text));
joy.setChannel(4, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH4.Text), revCH4.Checked, int.Parse(expo_ch4.Text));
joy.setChannel(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH5.Text), revCH5.Checked, int.Parse(expo_ch5.Text));
joy.setChannel(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH6.Text), revCH6.Checked, int.Parse(expo_ch6.Text));
joy.setChannel(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH7.Text), revCH7.Checked, int.Parse(expo_ch7.Text));
joy.setChannel(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH8.Text), revCH8.Checked, int.Parse(expo_ch8.Text));
joy.elevons = CHK_elevons.Checked;
@ -153,13 +173,6 @@ namespace ArdupilotMega
MainV2.joystick = null;
BUT_enable.Text = "Enable";
}
/*
MainV2.cs.rcoverridech1 = pickchannel(1, CMB_CH1.Text, revCH1.Checked, int.Parse(expo_ch1.Text));//(ushort)(((int)state.Rz / 65.535) + 1000);
MainV2.cs.rcoverridech2 = pickchannel(2, CMB_CH2.Text, revCH2.Checked, int.Parse(expo_ch2.Text));//(ushort)(((int)state.Y / 65.535) + 1000);
MainV2.cs.rcoverridech3 = pickchannel(3, CMB_CH3.Text, revCH3.Checked, int.Parse(expo_ch3.Text));//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000);
MainV2.cs.rcoverridech4 = pickchannel(4, CMB_CH4.Text, revCH4.Checked, int.Parse(expo_ch4.Text));//(ushort)(((int)state.X / 65.535) + 1000);
*/
}
private void BUT_save_Click(object sender, EventArgs e)
@ -169,18 +182,30 @@ namespace ArdupilotMega
MainV2.config["CMB_CH2"] = CMB_CH2.Text;
MainV2.config["CMB_CH3"] = CMB_CH3.Text;
MainV2.config["CMB_CH4"] = CMB_CH4.Text;
MainV2.config["CMB_CH5"] = CMB_CH5.Text;
MainV2.config["CMB_CH6"] = CMB_CH6.Text;
MainV2.config["CMB_CH7"] = CMB_CH7.Text;
MainV2.config["CMB_CH8"] = CMB_CH8.Text;
//revCH1
MainV2.config["revCH1"] = revCH1.Checked;
MainV2.config["revCH2"] = revCH2.Checked;
MainV2.config["revCH3"] = revCH3.Checked;
MainV2.config["revCH4"] = revCH4.Checked;
MainV2.config["revCH5"] = revCH5.Checked;
MainV2.config["revCH6"] = revCH6.Checked;
MainV2.config["revCH7"] = revCH7.Checked;
MainV2.config["revCH8"] = revCH8.Checked;
//expo_ch1
MainV2.config["expo_ch1"] = expo_ch1.Text;
MainV2.config["expo_ch2"] = expo_ch2.Text;
MainV2.config["expo_ch3"] = expo_ch3.Text;
MainV2.config["expo_ch4"] = expo_ch4.Text;
MainV2.config["expo_ch5"] = expo_ch5.Text;
MainV2.config["expo_ch6"] = expo_ch6.Text;
MainV2.config["expo_ch7"] = expo_ch7.Text;
MainV2.config["expo_ch8"] = expo_ch8.Text;
MainV2.config["joy_elevons"] = CHK_elevons.Checked;
@ -207,6 +232,10 @@ namespace ArdupilotMega
joy.setChannel(2, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH2.Text), revCH2.Checked, int.Parse(expo_ch2.Text));
joy.setChannel(3, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH3.Text), revCH3.Checked, int.Parse(expo_ch3.Text));
joy.setChannel(4, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH4.Text), revCH4.Checked, int.Parse(expo_ch4.Text));
joy.setChannel(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH5.Text), revCH5.Checked, int.Parse(expo_ch5.Text));
joy.setChannel(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH6.Text), revCH6.Checked, int.Parse(expo_ch6.Text));
joy.setChannel(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH7.Text), revCH7.Checked, int.Parse(expo_ch7.Text));
joy.setChannel(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH8.Text), revCH8.Checked, int.Parse(expo_ch8.Text));
joy.elevons = CHK_elevons.Checked;
@ -218,7 +247,7 @@ namespace ArdupilotMega
{
string name = (f + 1).ToString();
doButtontoUI(name, 10, 195 + f * 25);
doButtontoUI(name, 10, 290 + f * 25);
joy.setButton(f, int.Parse(this.Controls.Find("cmbbutton" + name, false)[0].Text), this.Controls.Find("cmbaction" + name, false)[0].Text);
}
@ -236,6 +265,10 @@ namespace ArdupilotMega
MainV2.cs.rcoverridech2 = joy.getValueForChannel(2, CMB_joysticks.Text);
MainV2.cs.rcoverridech3 = joy.getValueForChannel(3, CMB_joysticks.Text);
MainV2.cs.rcoverridech4 = joy.getValueForChannel(4, CMB_joysticks.Text);
MainV2.cs.rcoverridech5 = joy.getValueForChannel(5, CMB_joysticks.Text);
MainV2.cs.rcoverridech6 = joy.getValueForChannel(6, CMB_joysticks.Text);
MainV2.cs.rcoverridech7 = joy.getValueForChannel(7, CMB_joysticks.Text);
MainV2.cs.rcoverridech8 = joy.getValueForChannel(8, CMB_joysticks.Text);
//Console.WriteLine(DateTime.Now.Millisecond + " end ");
}
@ -246,6 +279,10 @@ namespace ArdupilotMega
progressBar2.Value = MainV2.cs.rcoverridech2;
progressBar3.Value = MainV2.cs.rcoverridech3;
progressBar4.Value = MainV2.cs.rcoverridech4;
horizontalProgressBar1.Value = MainV2.cs.rcoverridech5;
horizontalProgressBar2.Value = MainV2.cs.rcoverridech6;
horizontalProgressBar3.Value = MainV2.cs.rcoverridech7;
horizontalProgressBar4.Value = MainV2.cs.rcoverridech8;
try
{
@ -432,5 +469,77 @@ namespace ArdupilotMega
{
MainV2.joystick.elevons = CHK_elevons.Checked;
}
private void CMB_CH5_SelectedIndexChanged(object sender, EventArgs e)
{
if (startup || MainV2.joystick == null)
return;
MainV2.joystick.setAxis(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text));
}
private void CMB_CH6_SelectedIndexChanged(object sender, EventArgs e)
{
if (startup || MainV2.joystick == null)
return;
MainV2.joystick.setAxis(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text));
}
private void CMB_CH7_SelectedIndexChanged(object sender, EventArgs e)
{
if (startup || MainV2.joystick == null)
return;
MainV2.joystick.setAxis(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text));
}
private void CMB_CH8_SelectedIndexChanged(object sender, EventArgs e)
{
if (startup || MainV2.joystick == null)
return;
MainV2.joystick.setAxis(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text));
}
private void BUT_detch5_Click(object sender, EventArgs e)
{
CMB_CH5.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString();
}
private void BUT_detch6_Click(object sender, EventArgs e)
{
CMB_CH6.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString();
}
private void BUT_detch7_Click(object sender, EventArgs e)
{
CMB_CH7.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString();
}
private void BUT_detch8_Click(object sender, EventArgs e)
{
CMB_CH8.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString();
}
private void revCH5_CheckedChanged(object sender, EventArgs e)
{
if (MainV2.joystick != null)
MainV2.joystick.setReverse(5, ((CheckBox)sender).Checked);
}
private void revCH6_CheckedChanged(object sender, EventArgs e)
{
if (MainV2.joystick != null)
MainV2.joystick.setReverse(6, ((CheckBox)sender).Checked);
}
private void revCH7_CheckedChanged(object sender, EventArgs e)
{
if (MainV2.joystick != null)
MainV2.joystick.setReverse(7, ((CheckBox)sender).Checked);
}
private void revCH8_CheckedChanged(object sender, EventArgs e)
{
if (MainV2.joystick != null)
MainV2.joystick.setReverse(8, ((CheckBox)sender).Checked);
}
}
}

View File

@ -138,7 +138,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_joysticks.ZOrder" xml:space="preserve">
<value>32</value>
<value>56</value>
</data>
<data name="CMB_CH1.Items" xml:space="preserve">
<value>RZ</value>
@ -171,7 +171,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH1.ZOrder" xml:space="preserve">
<value>31</value>
<value>55</value>
</data>
<data name="CMB_CH2.Items" xml:space="preserve">
<value>RZ</value>
@ -204,7 +204,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH2.ZOrder" xml:space="preserve">
<value>30</value>
<value>54</value>
</data>
<data name="CMB_CH3.Items" xml:space="preserve">
<value>RZ</value>
@ -237,7 +237,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH3.ZOrder" xml:space="preserve">
<value>29</value>
<value>53</value>
</data>
<data name="CMB_CH4.Items" xml:space="preserve">
<value>RZ</value>
@ -270,7 +270,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH4.ZOrder" xml:space="preserve">
<value>28</value>
<value>52</value>
</data>
<data name="expo_ch1.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 70</value>
@ -294,7 +294,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch1.ZOrder" xml:space="preserve">
<value>23</value>
<value>47</value>
</data>
<data name="expo_ch2.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 97</value>
@ -318,7 +318,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch2.ZOrder" xml:space="preserve">
<value>22</value>
<value>46</value>
</data>
<data name="expo_ch3.Enabled" type="System.Boolean, mscorlib">
<value>False</value>
@ -345,7 +345,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch3.ZOrder" xml:space="preserve">
<value>21</value>
<value>45</value>
</data>
<data name="expo_ch4.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 151</value>
@ -369,7 +369,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch4.ZOrder" xml:space="preserve">
<value>20</value>
<value>44</value>
</data>
<data name="label1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -400,7 +400,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
<value>19</value>
<value>43</value>
</data>
<data name="label2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -430,7 +430,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label2.ZOrder" xml:space="preserve">
<value>18</value>
<value>42</value>
</data>
<data name="label3.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -460,7 +460,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label3.ZOrder" xml:space="preserve">
<value>17</value>
<value>41</value>
</data>
<data name="label4.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -490,7 +490,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label4.ZOrder" xml:space="preserve">
<value>16</value>
<value>40</value>
</data>
<data name="revCH1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -517,7 +517,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH1.ZOrder" xml:space="preserve">
<value>15</value>
<value>39</value>
</data>
<data name="revCH2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -544,7 +544,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH2.ZOrder" xml:space="preserve">
<value>14</value>
<value>38</value>
</data>
<data name="revCH3.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -571,7 +571,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH3.ZOrder" xml:space="preserve">
<value>13</value>
<value>37</value>
</data>
<data name="revCH4.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -598,7 +598,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH4.ZOrder" xml:space="preserve">
<value>12</value>
<value>36</value>
</data>
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -628,7 +628,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label5.ZOrder" xml:space="preserve">
<value>9</value>
<value>33</value>
</data>
<data name="label6.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -658,7 +658,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label6.ZOrder" xml:space="preserve">
<value>8</value>
<value>32</value>
</data>
<data name="label7.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -688,7 +688,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label7.ZOrder" xml:space="preserve">
<value>7</value>
<value>31</value>
</data>
<data name="label8.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -718,7 +718,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label8.ZOrder" xml:space="preserve">
<value>6</value>
<value>30</value>
</data>
<data name="label9.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -748,11 +748,548 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label9.ZOrder" xml:space="preserve">
<value>5</value>
<value>29</value>
</data>
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
</metadata>
<data name="CHK_elevons.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_elevons.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_elevons.Location" type="System.Drawing.Point, System.Drawing">
<value>434, 81</value>
</data>
<data name="CHK_elevons.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 17</value>
</data>
<data name="CHK_elevons.TabIndex" type="System.Int32, mscorlib">
<value>32</value>
</data>
<data name="CHK_elevons.Text" xml:space="preserve">
<value>Elevons</value>
</data>
<data name="&gt;&gt;CHK_elevons.Name" xml:space="preserve">
<value>CHK_elevons</value>
</data>
<data name="&gt;&gt;CHK_elevons.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_elevons.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_elevons.ZOrder" xml:space="preserve">
<value>24</value>
</data>
<data name="revCH5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH5.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 179</value>
</data>
<data name="revCH5.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH5.TabIndex" type="System.Int32, mscorlib">
<value>37</value>
</data>
<data name="&gt;&gt;revCH5.Name" xml:space="preserve">
<value>revCH5</value>
</data>
<data name="&gt;&gt;revCH5.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH5.ZOrder" xml:space="preserve">
<value>19</value>
</data>
<data name="label10.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label10.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label10.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 181</value>
</data>
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label10.TabIndex" type="System.Int32, mscorlib">
<value>36</value>
</data>
<data name="label10.Text" xml:space="preserve">
<value>CH 5</value>
</data>
<data name="&gt;&gt;label10.Name" xml:space="preserve">
<value>label10</value>
</data>
<data name="&gt;&gt;label10.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label10.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label10.ZOrder" xml:space="preserve">
<value>20</value>
</data>
<data name="expo_ch5.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 180</value>
</data>
<data name="expo_ch5.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch5.TabIndex" type="System.Int32, mscorlib">
<value>35</value>
</data>
<data name="expo_ch5.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch5.Name" xml:space="preserve">
<value>expo_ch5</value>
</data>
<data name="&gt;&gt;expo_ch5.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch5.ZOrder" xml:space="preserve">
<value>21</value>
</data>
<data name="CMB_CH5.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH5.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH5.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH5.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH5.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 176</value>
</data>
<data name="CMB_CH5.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH5.TabIndex" type="System.Int32, mscorlib">
<value>33</value>
</data>
<data name="&gt;&gt;CMB_CH5.Name" xml:space="preserve">
<value>CMB_CH5</value>
</data>
<data name="&gt;&gt;CMB_CH5.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH5.ZOrder" xml:space="preserve">
<value>23</value>
</data>
<data name="revCH6.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH6.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 208</value>
</data>
<data name="revCH6.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH6.TabIndex" type="System.Int32, mscorlib">
<value>43</value>
</data>
<data name="&gt;&gt;revCH6.Name" xml:space="preserve">
<value>revCH6</value>
</data>
<data name="&gt;&gt;revCH6.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH6.ZOrder" xml:space="preserve">
<value>13</value>
</data>
<data name="label11.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label11.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label11.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 210</value>
</data>
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label11.TabIndex" type="System.Int32, mscorlib">
<value>42</value>
</data>
<data name="label11.Text" xml:space="preserve">
<value>CH 6</value>
</data>
<data name="&gt;&gt;label11.Name" xml:space="preserve">
<value>label11</value>
</data>
<data name="&gt;&gt;label11.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label11.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label11.ZOrder" xml:space="preserve">
<value>14</value>
</data>
<data name="expo_ch6.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 209</value>
</data>
<data name="expo_ch6.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch6.TabIndex" type="System.Int32, mscorlib">
<value>41</value>
</data>
<data name="expo_ch6.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch6.Name" xml:space="preserve">
<value>expo_ch6</value>
</data>
<data name="&gt;&gt;expo_ch6.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch6.ZOrder" xml:space="preserve">
<value>15</value>
</data>
<data name="CMB_CH6.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH6.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH6.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH6.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH6.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 205</value>
</data>
<data name="CMB_CH6.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH6.TabIndex" type="System.Int32, mscorlib">
<value>39</value>
</data>
<data name="&gt;&gt;CMB_CH6.Name" xml:space="preserve">
<value>CMB_CH6</value>
</data>
<data name="&gt;&gt;CMB_CH6.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH6.ZOrder" xml:space="preserve">
<value>17</value>
</data>
<data name="revCH7.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH7.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH7.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 237</value>
</data>
<data name="revCH7.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH7.TabIndex" type="System.Int32, mscorlib">
<value>49</value>
</data>
<data name="&gt;&gt;revCH7.Name" xml:space="preserve">
<value>revCH7</value>
</data>
<data name="&gt;&gt;revCH7.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH7.ZOrder" xml:space="preserve">
<value>7</value>
</data>
<data name="label12.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label12.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label12.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 239</value>
</data>
<data name="label12.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label12.TabIndex" type="System.Int32, mscorlib">
<value>48</value>
</data>
<data name="label12.Text" xml:space="preserve">
<value>CH 7</value>
</data>
<data name="&gt;&gt;label12.Name" xml:space="preserve">
<value>label12</value>
</data>
<data name="&gt;&gt;label12.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label12.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label12.ZOrder" xml:space="preserve">
<value>8</value>
</data>
<data name="expo_ch7.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 238</value>
</data>
<data name="expo_ch7.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch7.TabIndex" type="System.Int32, mscorlib">
<value>47</value>
</data>
<data name="expo_ch7.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch7.Name" xml:space="preserve">
<value>expo_ch7</value>
</data>
<data name="&gt;&gt;expo_ch7.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch7.ZOrder" xml:space="preserve">
<value>9</value>
</data>
<data name="CMB_CH7.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH7.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH7.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH7.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH7.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 234</value>
</data>
<data name="CMB_CH7.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH7.TabIndex" type="System.Int32, mscorlib">
<value>45</value>
</data>
<data name="&gt;&gt;CMB_CH7.Name" xml:space="preserve">
<value>CMB_CH7</value>
</data>
<data name="&gt;&gt;CMB_CH7.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH7.ZOrder" xml:space="preserve">
<value>11</value>
</data>
<data name="revCH8.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH8.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH8.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 266</value>
</data>
<data name="revCH8.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH8.TabIndex" type="System.Int32, mscorlib">
<value>55</value>
</data>
<data name="&gt;&gt;revCH8.Name" xml:space="preserve">
<value>revCH8</value>
</data>
<data name="&gt;&gt;revCH8.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH8.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="label13.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label13.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label13.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 268</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label13.TabIndex" type="System.Int32, mscorlib">
<value>54</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>CH 8</value>
</data>
<data name="&gt;&gt;label13.Name" xml:space="preserve">
<value>label13</value>
</data>
<data name="&gt;&gt;label13.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label13.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label13.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="expo_ch8.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 267</value>
</data>
<data name="expo_ch8.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch8.TabIndex" type="System.Int32, mscorlib">
<value>53</value>
</data>
<data name="expo_ch8.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch8.Name" xml:space="preserve">
<value>expo_ch8</value>
</data>
<data name="&gt;&gt;expo_ch8.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch8.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="CMB_CH8.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH8.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH8.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH8.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH8.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 263</value>
</data>
<data name="CMB_CH8.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH8.TabIndex" type="System.Int32, mscorlib">
<value>51</value>
</data>
<data name="&gt;&gt;CMB_CH8.Name" xml:space="preserve">
<value>CMB_CH8</value>
</data>
<data name="&gt;&gt;CMB_CH8.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH8.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="BUT_detch8.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_detch8.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 263</value>
</data>
<data name="BUT_detch8.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="BUT_detch8.TabIndex" type="System.Int32, mscorlib">
<value>56</value>
</data>
<data name="BUT_detch8.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;BUT_detch8.Name" xml:space="preserve">
<value>BUT_detch8</value>
</data>
<data name="&gt;&gt;BUT_detch8.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch8.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="horizontalProgressBar4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar4.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 262</value>
</data>
<data name="horizontalProgressBar4.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar4.TabIndex" type="System.Int32, mscorlib">
<value>52</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.Name" xml:space="preserve">
<value>horizontalProgressBar4</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="BUT_detch4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
@ -778,7 +1315,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch4.ZOrder" xml:space="preserve">
<value>1</value>
<value>25</value>
</data>
<data name="BUT_detch3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -805,7 +1342,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch3.ZOrder" xml:space="preserve">
<value>2</value>
<value>26</value>
</data>
<data name="BUT_detch2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -832,7 +1369,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch2.ZOrder" xml:space="preserve">
<value>3</value>
<value>27</value>
</data>
<data name="BUT_detch1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -859,7 +1396,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch1.ZOrder" xml:space="preserve">
<value>4</value>
<value>28</value>
</data>
<data name="BUT_enable.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -886,7 +1423,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_enable.ZOrder" xml:space="preserve">
<value>10</value>
<value>34</value>
</data>
<data name="BUT_save.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -913,7 +1450,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_save.ZOrder" xml:space="preserve">
<value>11</value>
<value>35</value>
</data>
<data name="progressBar4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -937,7 +1474,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar4.ZOrder" xml:space="preserve">
<value>24</value>
<value>48</value>
</data>
<data name="progressBar3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -961,7 +1498,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar3.ZOrder" xml:space="preserve">
<value>25</value>
<value>49</value>
</data>
<data name="progressBar2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -985,7 +1522,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar2.ZOrder" xml:space="preserve">
<value>26</value>
<value>50</value>
</data>
<data name="progressBar1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1009,34 +1546,160 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar1.ZOrder" xml:space="preserve">
<value>27</value>
<value>51</value>
</data>
<data name="CHK_elevons.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
<data name="BUT_detch5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_elevons.Location" type="System.Drawing.Point, System.Drawing">
<value>434, 81</value>
<data name="BUT_detch5.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 176</value>
</data>
<data name="CHK_elevons.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 17</value>
<data name="BUT_detch5.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="CHK_elevons.TabIndex" type="System.Int32, mscorlib">
<value>32</value>
<data name="BUT_detch5.TabIndex" type="System.Int32, mscorlib">
<value>38</value>
</data>
<data name="CHK_elevons.Text" xml:space="preserve">
<value>Elevons</value>
<data name="BUT_detch5.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;CHK_elevons.Name" xml:space="preserve">
<value>CHK_elevons</value>
<data name="&gt;&gt;BUT_detch5.Name" xml:space="preserve">
<value>BUT_detch5</value>
</data>
<data name="&gt;&gt;CHK_elevons.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
<data name="&gt;&gt;BUT_detch5.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;CHK_elevons.Parent" xml:space="preserve">
<data name="&gt;&gt;BUT_detch5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_elevons.ZOrder" xml:space="preserve">
<value>0</value>
<data name="&gt;&gt;BUT_detch5.ZOrder" xml:space="preserve">
<value>18</value>
</data>
<data name="horizontalProgressBar1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar1.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 175</value>
</data>
<data name="horizontalProgressBar1.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar1.TabIndex" type="System.Int32, mscorlib">
<value>34</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.Name" xml:space="preserve">
<value>horizontalProgressBar1</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.ZOrder" xml:space="preserve">
<value>22</value>
</data>
<data name="BUT_detch6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_detch6.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 205</value>
</data>
<data name="BUT_detch6.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="BUT_detch6.TabIndex" type="System.Int32, mscorlib">
<value>44</value>
</data>
<data name="BUT_detch6.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;BUT_detch6.Name" xml:space="preserve">
<value>BUT_detch6</value>
</data>
<data name="&gt;&gt;BUT_detch6.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch6.ZOrder" xml:space="preserve">
<value>12</value>
</data>
<data name="horizontalProgressBar2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar2.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 204</value>
</data>
<data name="horizontalProgressBar2.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar2.TabIndex" type="System.Int32, mscorlib">
<value>40</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.Name" xml:space="preserve">
<value>horizontalProgressBar2</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.ZOrder" xml:space="preserve">
<value>16</value>
</data>
<data name="BUT_detch7.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_detch7.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 234</value>
</data>
<data name="BUT_detch7.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="BUT_detch7.TabIndex" type="System.Int32, mscorlib">
<value>50</value>
</data>
<data name="BUT_detch7.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;BUT_detch7.Name" xml:space="preserve">
<value>BUT_detch7</value>
</data>
<data name="&gt;&gt;BUT_detch7.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch7.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="horizontalProgressBar3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar3.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 233</value>
</data>
<data name="horizontalProgressBar3.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar3.TabIndex" type="System.Int32, mscorlib">
<value>46</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.Name" xml:space="preserve">
<value>horizontalProgressBar3</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.ZOrder" xml:space="preserve">
<value>10</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
@ -1045,7 +1708,7 @@
<value>6, 13</value>
</data>
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
<value>498, 220</value>
<value>498, 331</value>
</data>
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>

View File

@ -23,11 +23,11 @@ namespace ArdupilotMega
public byte sysid = 0;
public byte compid = 0;
public Hashtable param = new Hashtable();
public static byte[][] packets = new byte[256][];
public byte[][] packets = new byte[256][];
public double[] packetspersecond = new double[256];
DateTime[] packetspersecondbuild = new DateTime[256];
static object objlock = new object();
static object readlock = new object();
object objlock = new object();
object readlock = new object();
object logwritelock = new object();
public DateTime lastvalidpacket = DateTime.Now;
bool oldlogformat = false;
@ -44,7 +44,7 @@ namespace ArdupilotMega
public BinaryReader logplaybackfile = null;
public BinaryWriter logfile = null;
public static byte[] streams = new byte[256];
public byte[] streams = new byte[256];
int bps1 = 0;
int bps2 = 0;

View File

@ -66,10 +66,10 @@ namespace ArdupilotMega
GCSViews.FlightData FlightData;
GCSViews.FlightPlanner FlightPlanner;
//GCSViews.Configuration Configuration;
GCSViews.Configuration Configuration;
GCSViews.Simulation Simulation;
GCSViews.Firmware Firmware;
//GCSViews.Terminal Terminal;
GCSViews.Terminal Terminal;
public MainV2()
{
@ -221,6 +221,22 @@ namespace ArdupilotMega
splash.Close();
}
internal void ScreenShot()
{
Rectangle bounds = Screen.GetBounds(Point.Empty);
using (Bitmap bitmap = new Bitmap(bounds.Width, bounds.Height))
{
using (Graphics g = Graphics.FromImage(bitmap))
{
g.CopyFromScreen(Point.Empty, Point.Empty, bounds.Size);
}
string name = "ss" + DateTime.Now.ToString("hhmmss") + ".jpg";
bitmap.Save(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + name, System.Drawing.Imaging.ImageFormat.Jpeg);
MessageBox.Show("Screenshot saved to " + name);
}
}
private void CMB_serialport_Click(object sender, EventArgs e)
{
string oldport = CMB_serialport.Text;
@ -456,7 +472,19 @@ namespace ArdupilotMega
GCSViews.Terminal.threadrun = false;
UserControl temp = new GCSViews.Configuration();
// dispose of old else memory leak
if (Configuration != null)
{
try
{
Configuration.Dispose();
}
catch { }
}
Configuration = new GCSViews.Configuration();
UserControl temp = Configuration;
temp.SuspendLayout();
@ -633,6 +661,8 @@ namespace ArdupilotMega
cs.firmware = APMFirmware;
config[CMB_serialport.Text + "_BAUD"] = CMB_baudrate.Text;
if (config["loadwpsonconnect"] != null && bool.Parse(config["loadwpsonconnect"].ToString()) == true)
{
MenuFlightPlanner_Click(null, null);
@ -697,6 +727,9 @@ namespace ArdupilotMega
try
{
comPort.BaseStream.PortName = CMB_serialport.Text;
if (config[CMB_serialport.Text + "_BAUD"] != null)
CMB_baudrate.Text = config[CMB_serialport.Text + "_BAUD"].ToString();
}
catch { }
}
@ -874,10 +907,22 @@ namespace ArdupilotMega
rc.target_component = comPort.compid;
rc.target_system = comPort.sysid;
rc.chan1_raw = cs.rcoverridech1;//(ushort)(((int)state.Rz / 65.535) + 1000);
rc.chan2_raw = cs.rcoverridech2;//(ushort)(((int)state.Y / 65.535) + 1000);
rc.chan3_raw = cs.rcoverridech3;//(ushort)(1000 - ((int)slider[0] / 65.535 ) + 1000);
rc.chan4_raw = cs.rcoverridech4;//(ushort)(((int)state.X / 65.535) + 1000);
if (joystick.getJoystickAxis(1) != Joystick.joystickaxis.None)
rc.chan1_raw = cs.rcoverridech1;//(ushort)(((int)state.Rz / 65.535) + 1000);
if (joystick.getJoystickAxis(2) != Joystick.joystickaxis.None)
rc.chan2_raw = cs.rcoverridech2;//(ushort)(((int)state.Y / 65.535) + 1000);
if (joystick.getJoystickAxis(3) != Joystick.joystickaxis.None)
rc.chan3_raw = cs.rcoverridech3;//(ushort)(1000 - ((int)slider[0] / 65.535 ) + 1000);
if (joystick.getJoystickAxis(4) != Joystick.joystickaxis.None)
rc.chan4_raw = cs.rcoverridech4;//(ushort)(((int)state.X / 65.535) + 1000);
if (joystick.getJoystickAxis(5) != Joystick.joystickaxis.None)
rc.chan5_raw = cs.rcoverridech5;
if (joystick.getJoystickAxis(6) != Joystick.joystickaxis.None)
rc.chan6_raw = cs.rcoverridech6;
if (joystick.getJoystickAxis(7) != Joystick.joystickaxis.None)
rc.chan7_raw = cs.rcoverridech7;
if (joystick.getJoystickAxis(8) != Joystick.joystickaxis.None)
rc.chan8_raw = cs.rcoverridech8;
if (lastjoystick.AddMilliseconds(50) < DateTime.Now)
{
@ -1545,6 +1590,11 @@ namespace ArdupilotMega
frm.Show();
return true;
}
if (keyData == (Keys.Control | Keys.S))
{
ScreenShot();
return true;
}
if (keyData == (Keys.Control | Keys.G)) // test
{
Form frm = new SerialOutput();

View File

@ -137,7 +137,7 @@ namespace ArdupilotMega
flyto.Duration = (cs.datetime - lasttime).TotalMilliseconds / 1000.0;
flyto.Mode = FlyToMode.Smooth;
Camera cam = new Camera();
SharpKml.Dom.Camera cam = new SharpKml.Dom.Camera();
cam.AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute;
cam.Latitude = cs.lat;
cam.Longitude = cs.lng;
@ -316,7 +316,7 @@ namespace ArdupilotMega
mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
mine.logreadmode = true;
MAVLink.packets.Initialize(); // clear
mine.packets.Initialize(); // clear
CurrentState cs = new CurrentState();
@ -422,7 +422,7 @@ namespace ArdupilotMega
mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
mine.logreadmode = true;
MAVLink.packets.Initialize(); // clear
mine.packets.Initialize(); // clear
StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile)+ Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".txt");

View File

@ -24,6 +24,7 @@ namespace ArdupilotMega
Application.EnableVisualStyles();
Application.SetCompatibleTextRenderingDefault(false);
//Application.Run(new Camera());
Application.Run(new MainV2());
}

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.0.84")]
[assembly: AssemblyFileVersion("1.0.86")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -14,7 +14,8 @@ namespace ArdupilotMega
{
System.Threading.Thread t12;
static bool threadrun = false;
static SerialPort comPort = new SerialPort();
static internal SerialPort comPort = new SerialPort();
static internal PointLatLngAlt HomeLoc = new PointLatLngAlt(0,0,0,"Home");
public SerialOutput()
{
@ -62,6 +63,7 @@ namespace ArdupilotMega
void mainloop()
{
threadrun = true;
int counter = 0;
while (threadrun)
{
try
@ -78,7 +80,16 @@ namespace ArdupilotMega
checksum = GetChecksum(line);
comPort.WriteLine(line + "*" + checksum);
if (counter % 5 == 0 && HomeLoc.Lat != 0 && HomeLoc.Lng != 0)
{
line = string.Format("$GP{0},{1:HHmmss},{2},{3},{4},{5},{6},{7},", "HOM", DateTime.Now.ToUniversalTime(), Math.Abs(HomeLoc.Lat * 100), HomeLoc.Lat < 0 ? "S" : "N", Math.Abs(HomeLoc.Lng * 100), HomeLoc.Lng < 0 ? "W" : "E", HomeLoc.Alt, "M");
checksum = GetChecksum(line);
comPort.WriteLine(line + "*" + checksum);
}
System.Threading.Thread.Sleep(500);
counter++;
}
catch { }
}

View File

@ -53,7 +53,7 @@
<StartupObject />
</PropertyGroup>
<PropertyGroup>
<SignAssembly>true</SignAssembly>
<SignAssembly>false</SignAssembly>
</PropertyGroup>
<PropertyGroup>
<AssemblyOriginatorKeyFile>mykey.pfx</AssemblyOriginatorKeyFile>

View File

@ -11,7 +11,7 @@
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
</dsig:Transforms>
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
<dsig:DigestValue>sVd4w+f3LroCsyok5UsAi4Bq9eI=</dsig:DigestValue>
<dsig:DigestValue>FgyYFBDKA+EmX+ZazsEdbI/ME7o=</dsig:DigestValue>
</hash>
</dependentAssembly>
</dependency>

View File

@ -134,7 +134,7 @@
<value>Point Camera Here</value>
</data>
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
<value>175, 70</value>
<value>175, 48</value>
</data>
<data name="&gt;&gt;contextMenuStrip1.Name" xml:space="preserve">
<value>contextMenuStrip1</value>
@ -1083,290 +1083,68 @@
<data name="MainH.Panel1MinSize" type="System.Int32, mscorlib">
<value>360</value>
</data>
<data name="tableMap.CellBorderStyle" type="System.Windows.Forms.TableLayoutPanelCellBorderStyle, System.Windows.Forms">
<value>Single</value>
</data>
<data name="tableMap.ColumnCount" type="System.Int32, mscorlib">
<value>1</value>
</data>
<data name="TXT_lat.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_lat.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_lat.Location" type="System.Drawing.Point, System.Drawing">
<value>10, 10</value>
</data>
<data name="TXT_lat.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_lat.TabIndex" type="System.Int32, mscorlib">
<value>13</value>
</data>
<data name="TXT_lat.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_lat.Name" xml:space="preserve">
<value>TXT_lat</value>
</data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_lat.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="Zoomlevel.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="Zoomlevel.Location" type="System.Drawing.Point, System.Drawing">
<value>438, 7</value>
</data>
<data name="Zoomlevel.Size" type="System.Drawing.Size, System.Drawing">
<value>76, 20</value>
</data>
<data name="Zoomlevel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="Zoomlevel.ToolTip" xml:space="preserve">
<value>Change Zoom Level</value>
</data>
<data name="&gt;&gt;Zoomlevel.Name" xml:space="preserve">
<value>Zoomlevel</value>
</data>
<data name="&gt;&gt;Zoomlevel.Type" xml:space="preserve">
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;Zoomlevel.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;Zoomlevel.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="label1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="label1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>401, 10</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label1.TabIndex" type="System.Int32, mscorlib">
<value>70</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>Zoom</value>
</data>
<data name="&gt;&gt;label1.Name" xml:space="preserve">
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="TXT_long.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_long.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_long.Location" type="System.Drawing.Point, System.Drawing">
<value>100, 10</value>
</data>
<data name="TXT_long.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_long.TabIndex" type="System.Int32, mscorlib">
<value>14</value>
</data>
<data name="TXT_long.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_long.Name" xml:space="preserve">
<value>TXT_long</value>
</data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_long.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="TXT_alt.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_alt.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_alt.Location" type="System.Drawing.Point, System.Drawing">
<value>190, 10</value>
</data>
<data name="TXT_alt.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="TXT_alt.TabIndex" type="System.Int32, mscorlib">
<value>15</value>
</data>
<data name="TXT_alt.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_alt.Name" xml:space="preserve">
<value>TXT_alt</value>
</data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_alt.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="CHK_autopan.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CHK_autopan.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_autopan.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_autopan.Location" type="System.Drawing.Point, System.Drawing">
<value>325, 10</value>
</data>
<data name="CHK_autopan.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 17</value>
</data>
<data name="CHK_autopan.TabIndex" type="System.Int32, mscorlib">
<value>68</value>
</data>
<data name="CHK_autopan.Text" xml:space="preserve">
<value>Auto Pan</value>
</data>
<data name="CHK_autopan.ToolTip" xml:space="preserve">
<value>Makes the map autopan based on current location</value>
</data>
<data name="&gt;&gt;CHK_autopan.Name" xml:space="preserve">
<value>CHK_autopan</value>
</data>
<data name="&gt;&gt;CHK_autopan.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_autopan.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CHK_autopan.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="CB_tuning.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CB_tuning.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CB_tuning.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CB_tuning.Location" type="System.Drawing.Point, System.Drawing">
<value>260, 9</value>
</data>
<data name="CB_tuning.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="CB_tuning.TabIndex" type="System.Int32, mscorlib">
<value>62</value>
</data>
<data name="CB_tuning.Text" xml:space="preserve">
<value>Tuning</value>
</data>
<data name="CB_tuning.ToolTip" xml:space="preserve">
<value>Show the tunning graph, chowing target attitudes vs actual</value>
</data>
<data name="&gt;&gt;CB_tuning.Name" xml:space="preserve">
<value>CB_tuning</value>
</data>
<data name="&gt;&gt;CB_tuning.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CB_tuning.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CB_tuning.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="panel1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<data name="splitContainer1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel1.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 429</value>
<data name="splitContainer1.Location" type="System.Drawing.Point, System.Drawing">
<value>4, 4</value>
</data>
<data name="panel1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
<data name="splitContainer1.Orientation" type="System.Windows.Forms.Orientation, System.Windows.Forms">
<value>Horizontal</value>
</data>
<data name="panel1.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 30</value>
<data name="zg1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel1.TabIndex" type="System.Int32, mscorlib">
<data name="zg1.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
</data>
<data name="zg1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>4, 4, 4, 4</value>
</data>
<data name="zg1.Size" type="System.Drawing.Size, System.Drawing">
<value>577, 210</value>
</data>
<data name="zg1.TabIndex" type="System.Int32, mscorlib">
<value>67</value>
</data>
<data name="zg1.Visible" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="&gt;&gt;zg1.Name" xml:space="preserve">
<value>zg1</value>
</data>
<data name="&gt;&gt;zg1.Type" xml:space="preserve">
<value>ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60</value>
</data>
<data name="&gt;&gt;zg1.Parent" xml:space="preserve">
<value>splitContainer1.Panel1</value>
</data>
<data name="&gt;&gt;zg1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;panel1.Name" xml:space="preserve">
<value>panel1</value>
<data name="&gt;&gt;splitContainer1.Panel1.Name" xml:space="preserve">
<value>splitContainer1.Panel1</value>
</data>
<data name="&gt;&gt;panel1.Type" xml:space="preserve">
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
<data name="&gt;&gt;splitContainer1.Panel1.Type" xml:space="preserve">
<value>System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;panel1.Parent" xml:space="preserve">
<value>tableMap</value>
<data name="&gt;&gt;splitContainer1.Panel1.Parent" xml:space="preserve">
<value>splitContainer1</value>
</data>
<data name="&gt;&gt;panel1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_windvel.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_windvel.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 21</value>
</data>
<data name="lbl_windvel.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="lbl_windvel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="lbl_windvel.Text" xml:space="preserve">
<value>Vel: 0</value>
</data>
<data name="lbl_windvel.ToolTip" xml:space="preserve">
<value>Estimated Wind Velocity</value>
</data>
<data name="&gt;&gt;lbl_windvel.Name" xml:space="preserve">
<value>lbl_windvel</value>
</data>
<data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
<value>panel2</value>
</data>
<data name="&gt;&gt;lbl_windvel.ZOrder" xml:space="preserve">
<data name="&gt;&gt;splitContainer1.Panel1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_winddir.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_winddir.Location" type="System.Drawing.Point, System.Drawing">
<value>7, 8</value>
<value>4, 7</value>
</data>
<data name="lbl_winddir.Size" type="System.Drawing.Size, System.Drawing">
<value>32, 13</value>
@ -1387,9 +1165,39 @@
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;lbl_winddir.Parent" xml:space="preserve">
<value>panel2</value>
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_winddir.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="lbl_windvel.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="lbl_windvel.Location" type="System.Drawing.Point, System.Drawing">
<value>4, 20</value>
</data>
<data name="lbl_windvel.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="lbl_windvel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="lbl_windvel.Text" xml:space="preserve">
<value>Vel: 0</value>
</data>
<data name="lbl_windvel.ToolTip" xml:space="preserve">
<value>Estimated Wind Velocity</value>
</data>
<data name="&gt;&gt;lbl_windvel.Name" xml:space="preserve">
<value>lbl_windvel</value>
</data>
<data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;lbl_windvel.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="gMapControl1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
@ -1402,7 +1210,7 @@
<value>0, 0, 0, 0</value>
</data>
<data name="gMapControl1.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 429</value>
<value>577, 420</value>
</data>
<data name="gMapControl1.streamjpg" mimetype="application/x-microsoft.net.object.binary.base64">
<value>
@ -1559,66 +1367,288 @@
<value>GMap.NET.WindowsForms.GMapControl, GMap.NET.WindowsForms, Version=1.5.5.5, Culture=neutral, PublicKeyToken=b85b9027b614afef</value>
</data>
<data name="&gt;&gt;gMapControl1.Parent" xml:space="preserve">
<value>panel2</value>
<value>splitContainer1.Panel2</value>
</data>
<data name="&gt;&gt;gMapControl1.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="zg1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
<data name="&gt;&gt;splitContainer1.Panel2.Name" xml:space="preserve">
<value>splitContainer1.Panel2</value>
</data>
<data name="zg1.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
<data name="&gt;&gt;splitContainer1.Panel2.Type" xml:space="preserve">
<value>System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="zg1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>4, 4, 4, 4</value>
<data name="&gt;&gt;splitContainer1.Panel2.Parent" xml:space="preserve">
<value>splitContainer1</value>
</data>
<data name="zg1.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 429</value>
</data>
<data name="zg1.TabIndex" type="System.Int32, mscorlib">
<value>67</value>
</data>
<data name="zg1.Visible" type="System.Boolean, mscorlib">
<value>False</value>
</data>
<data name="&gt;&gt;zg1.Name" xml:space="preserve">
<value>zg1</value>
</data>
<data name="&gt;&gt;zg1.Type" xml:space="preserve">
<value>ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60</value>
</data>
<data name="&gt;&gt;zg1.Parent" xml:space="preserve">
<value>panel2</value>
</data>
<data name="&gt;&gt;zg1.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="panel2.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel2.Location" type="System.Drawing.Point, System.Drawing">
<value>0, 0</value>
</data>
<data name="panel2.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
</data>
<data name="panel2.Size" type="System.Drawing.Size, System.Drawing">
<value>585, 429</value>
</data>
<data name="panel2.TabIndex" type="System.Int32, mscorlib">
<data name="&gt;&gt;splitContainer1.Panel2.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="&gt;&gt;panel2.Name" xml:space="preserve">
<value>panel2</value>
<data name="splitContainer1.Size" type="System.Drawing.Size, System.Drawing">
<value>577, 420</value>
</data>
<data name="&gt;&gt;panel2.Type" xml:space="preserve">
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
<data name="splitContainer1.SplitterDistance" type="System.Int32, mscorlib">
<value>210</value>
</data>
<data name="&gt;&gt;panel2.Parent" xml:space="preserve">
<data name="splitContainer1.TabIndex" type="System.Int32, mscorlib">
<value>76</value>
</data>
<data name="&gt;&gt;splitContainer1.Name" xml:space="preserve">
<value>splitContainer1</value>
</data>
<data name="&gt;&gt;splitContainer1.Type" xml:space="preserve">
<value>System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;splitContainer1.Parent" xml:space="preserve">
<value>tableMap</value>
</data>
<data name="&gt;&gt;panel2.ZOrder" xml:space="preserve">
<data name="&gt;&gt;splitContainer1.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="TXT_lat.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_lat.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_lat.Location" type="System.Drawing.Point, System.Drawing">
<value>10, 11</value>
</data>
<data name="TXT_lat.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_lat.TabIndex" type="System.Int32, mscorlib">
<value>13</value>
</data>
<data name="TXT_lat.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_lat.Name" xml:space="preserve">
<value>TXT_lat</value>
</data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_lat.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="Zoomlevel.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="Zoomlevel.Location" type="System.Drawing.Point, System.Drawing">
<value>438, 8</value>
</data>
<data name="Zoomlevel.Size" type="System.Drawing.Size, System.Drawing">
<value>76, 20</value>
</data>
<data name="Zoomlevel.TabIndex" type="System.Int32, mscorlib">
<value>69</value>
</data>
<data name="Zoomlevel.ToolTip" xml:space="preserve">
<value>Change Zoom Level</value>
</data>
<data name="&gt;&gt;Zoomlevel.Name" xml:space="preserve">
<value>Zoomlevel</value>
</data>
<data name="&gt;&gt;Zoomlevel.Type" xml:space="preserve">
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;Zoomlevel.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;Zoomlevel.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="label1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="label1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
<value>401, 11</value>
</data>
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
<value>34, 13</value>
</data>
<data name="label1.TabIndex" type="System.Int32, mscorlib">
<value>70</value>
</data>
<data name="label1.Text" xml:space="preserve">
<value>Zoom</value>
</data>
<data name="&gt;&gt;label1.Name" xml:space="preserve">
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="TXT_long.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_long.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_long.Location" type="System.Drawing.Point, System.Drawing">
<value>100, 11</value>
</data>
<data name="TXT_long.Size" type="System.Drawing.Size, System.Drawing">
<value>84, 13</value>
</data>
<data name="TXT_long.TabIndex" type="System.Int32, mscorlib">
<value>14</value>
</data>
<data name="TXT_long.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_long.Name" xml:space="preserve">
<value>TXT_long</value>
</data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_long.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="TXT_alt.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="TXT_alt.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="TXT_alt.Location" type="System.Drawing.Point, System.Drawing">
<value>190, 11</value>
</data>
<data name="TXT_alt.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 13</value>
</data>
<data name="TXT_alt.TabIndex" type="System.Int32, mscorlib">
<value>15</value>
</data>
<data name="TXT_alt.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;TXT_alt.Name" xml:space="preserve">
<value>TXT_alt</value>
</data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;TXT_alt.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="CHK_autopan.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CHK_autopan.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_autopan.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_autopan.Location" type="System.Drawing.Point, System.Drawing">
<value>325, 11</value>
</data>
<data name="CHK_autopan.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 17</value>
</data>
<data name="CHK_autopan.TabIndex" type="System.Int32, mscorlib">
<value>68</value>
</data>
<data name="CHK_autopan.Text" xml:space="preserve">
<value>Auto Pan</value>
</data>
<data name="CHK_autopan.ToolTip" xml:space="preserve">
<value>Makes the map autopan based on current location</value>
</data>
<data name="&gt;&gt;CHK_autopan.Name" xml:space="preserve">
<value>CHK_autopan</value>
</data>
<data name="&gt;&gt;CHK_autopan.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_autopan.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CHK_autopan.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="CB_tuning.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
<value>Bottom, Left</value>
</data>
<data name="CB_tuning.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CB_tuning.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CB_tuning.Location" type="System.Drawing.Point, System.Drawing">
<value>260, 10</value>
</data>
<data name="CB_tuning.Size" type="System.Drawing.Size, System.Drawing">
<value>59, 17</value>
</data>
<data name="CB_tuning.TabIndex" type="System.Int32, mscorlib">
<value>62</value>
</data>
<data name="CB_tuning.Text" xml:space="preserve">
<value>Tuning</value>
</data>
<data name="CB_tuning.ToolTip" xml:space="preserve">
<value>Show the tunning graph, chowing target attitudes vs actual</value>
</data>
<data name="&gt;&gt;CB_tuning.Name" xml:space="preserve">
<value>CB_tuning</value>
</data>
<data name="&gt;&gt;CB_tuning.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CB_tuning.Parent" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;CB_tuning.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="panel1.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
<value>Fill</value>
</data>
<data name="panel1.Location" type="System.Drawing.Point, System.Drawing">
<value>1, 428</value>
</data>
<data name="panel1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
<value>0, 0, 0, 0</value>
</data>
<data name="panel1.Size" type="System.Drawing.Size, System.Drawing">
<value>583, 30</value>
</data>
<data name="panel1.TabIndex" type="System.Int32, mscorlib">
<value>0</value>
</data>
<data name="&gt;&gt;panel1.Name" xml:space="preserve">
<value>panel1</value>
</data>
<data name="&gt;&gt;panel1.Type" xml:space="preserve">
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;panel1.Parent" xml:space="preserve">
<value>tableMap</value>
</data>
<data name="&gt;&gt;panel1.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="tableMap.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
@ -1649,7 +1679,7 @@
<value>0</value>
</data>
<data name="tableMap.LayoutSettings" type="System.Windows.Forms.TableLayoutSettings, System.Windows.Forms">
<value>&lt;?xml version="1.0" encoding="utf-16"?&gt;&lt;TableLayoutSettings&gt;&lt;Controls&gt;&lt;Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;Control Name="panel2" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;/Controls&gt;&lt;Columns Styles="Percent,100" /&gt;&lt;Rows Styles="Percent,100,Absolute,30" /&gt;&lt;/TableLayoutSettings&gt;</value>
<value>&lt;?xml version="1.0" encoding="utf-16"?&gt;&lt;TableLayoutSettings&gt;&lt;Controls&gt;&lt;Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /&gt;&lt;/Controls&gt;&lt;Columns Styles="Percent,100" /&gt;&lt;Rows Styles="Percent,100,Absolute,30,Absolute,20" /&gt;&lt;/TableLayoutSettings&gt;</value>
</data>
<data name="&gt;&gt;MainH.Panel2.Name" xml:space="preserve">
<value>MainH.Panel2</value>

View File

@ -138,7 +138,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_joysticks.ZOrder" xml:space="preserve">
<value>32</value>
<value>56</value>
</data>
<data name="CMB_CH1.Items" xml:space="preserve">
<value>RZ</value>
@ -171,7 +171,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH1.ZOrder" xml:space="preserve">
<value>31</value>
<value>55</value>
</data>
<data name="CMB_CH2.Items" xml:space="preserve">
<value>RZ</value>
@ -204,7 +204,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH2.ZOrder" xml:space="preserve">
<value>30</value>
<value>54</value>
</data>
<data name="CMB_CH3.Items" xml:space="preserve">
<value>RZ</value>
@ -237,7 +237,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH3.ZOrder" xml:space="preserve">
<value>29</value>
<value>53</value>
</data>
<data name="CMB_CH4.Items" xml:space="preserve">
<value>RZ</value>
@ -270,7 +270,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH4.ZOrder" xml:space="preserve">
<value>28</value>
<value>52</value>
</data>
<data name="expo_ch1.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 70</value>
@ -294,7 +294,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch1.ZOrder" xml:space="preserve">
<value>23</value>
<value>47</value>
</data>
<data name="expo_ch2.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 97</value>
@ -318,7 +318,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch2.ZOrder" xml:space="preserve">
<value>22</value>
<value>46</value>
</data>
<data name="expo_ch3.Enabled" type="System.Boolean, mscorlib">
<value>False</value>
@ -345,7 +345,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch3.ZOrder" xml:space="preserve">
<value>21</value>
<value>45</value>
</data>
<data name="expo_ch4.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 151</value>
@ -369,7 +369,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch4.ZOrder" xml:space="preserve">
<value>20</value>
<value>44</value>
</data>
<data name="label1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -400,7 +400,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
<value>19</value>
<value>43</value>
</data>
<data name="label2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -430,7 +430,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label2.ZOrder" xml:space="preserve">
<value>18</value>
<value>42</value>
</data>
<data name="label3.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -460,7 +460,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label3.ZOrder" xml:space="preserve">
<value>17</value>
<value>41</value>
</data>
<data name="label4.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -490,7 +490,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label4.ZOrder" xml:space="preserve">
<value>16</value>
<value>40</value>
</data>
<data name="revCH1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -517,7 +517,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH1.ZOrder" xml:space="preserve">
<value>15</value>
<value>39</value>
</data>
<data name="revCH2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -544,7 +544,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH2.ZOrder" xml:space="preserve">
<value>14</value>
<value>38</value>
</data>
<data name="revCH3.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -571,7 +571,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH3.ZOrder" xml:space="preserve">
<value>13</value>
<value>37</value>
</data>
<data name="revCH4.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -598,7 +598,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;revCH4.ZOrder" xml:space="preserve">
<value>12</value>
<value>36</value>
</data>
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -628,7 +628,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label5.ZOrder" xml:space="preserve">
<value>9</value>
<value>33</value>
</data>
<data name="label6.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -658,7 +658,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label6.ZOrder" xml:space="preserve">
<value>8</value>
<value>32</value>
</data>
<data name="label7.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -688,7 +688,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label7.ZOrder" xml:space="preserve">
<value>7</value>
<value>31</value>
</data>
<data name="label8.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -718,7 +718,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label8.ZOrder" xml:space="preserve">
<value>6</value>
<value>30</value>
</data>
<data name="label9.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
@ -748,11 +748,548 @@
<value>$this</value>
</data>
<data name="&gt;&gt;label9.ZOrder" xml:space="preserve">
<value>5</value>
<value>29</value>
</data>
<metadata name="timer1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
</metadata>
<data name="CHK_elevons.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="CHK_elevons.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_elevons.Location" type="System.Drawing.Point, System.Drawing">
<value>434, 81</value>
</data>
<data name="CHK_elevons.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 17</value>
</data>
<data name="CHK_elevons.TabIndex" type="System.Int32, mscorlib">
<value>32</value>
</data>
<data name="CHK_elevons.Text" xml:space="preserve">
<value>Elevons</value>
</data>
<data name="&gt;&gt;CHK_elevons.Name" xml:space="preserve">
<value>CHK_elevons</value>
</data>
<data name="&gt;&gt;CHK_elevons.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CHK_elevons.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_elevons.ZOrder" xml:space="preserve">
<value>24</value>
</data>
<data name="revCH5.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH5.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 179</value>
</data>
<data name="revCH5.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH5.TabIndex" type="System.Int32, mscorlib">
<value>37</value>
</data>
<data name="&gt;&gt;revCH5.Name" xml:space="preserve">
<value>revCH5</value>
</data>
<data name="&gt;&gt;revCH5.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH5.ZOrder" xml:space="preserve">
<value>19</value>
</data>
<data name="label10.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label10.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label10.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 181</value>
</data>
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label10.TabIndex" type="System.Int32, mscorlib">
<value>36</value>
</data>
<data name="label10.Text" xml:space="preserve">
<value>CH 5</value>
</data>
<data name="&gt;&gt;label10.Name" xml:space="preserve">
<value>label10</value>
</data>
<data name="&gt;&gt;label10.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label10.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label10.ZOrder" xml:space="preserve">
<value>20</value>
</data>
<data name="expo_ch5.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 180</value>
</data>
<data name="expo_ch5.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch5.TabIndex" type="System.Int32, mscorlib">
<value>35</value>
</data>
<data name="expo_ch5.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch5.Name" xml:space="preserve">
<value>expo_ch5</value>
</data>
<data name="&gt;&gt;expo_ch5.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch5.ZOrder" xml:space="preserve">
<value>21</value>
</data>
<data name="CMB_CH5.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH5.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH5.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH5.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH5.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 176</value>
</data>
<data name="CMB_CH5.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH5.TabIndex" type="System.Int32, mscorlib">
<value>33</value>
</data>
<data name="&gt;&gt;CMB_CH5.Name" xml:space="preserve">
<value>CMB_CH5</value>
</data>
<data name="&gt;&gt;CMB_CH5.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH5.ZOrder" xml:space="preserve">
<value>23</value>
</data>
<data name="revCH6.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH6.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 208</value>
</data>
<data name="revCH6.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH6.TabIndex" type="System.Int32, mscorlib">
<value>43</value>
</data>
<data name="&gt;&gt;revCH6.Name" xml:space="preserve">
<value>revCH6</value>
</data>
<data name="&gt;&gt;revCH6.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH6.ZOrder" xml:space="preserve">
<value>13</value>
</data>
<data name="label11.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label11.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label11.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 210</value>
</data>
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label11.TabIndex" type="System.Int32, mscorlib">
<value>42</value>
</data>
<data name="label11.Text" xml:space="preserve">
<value>CH 6</value>
</data>
<data name="&gt;&gt;label11.Name" xml:space="preserve">
<value>label11</value>
</data>
<data name="&gt;&gt;label11.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label11.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label11.ZOrder" xml:space="preserve">
<value>14</value>
</data>
<data name="expo_ch6.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 209</value>
</data>
<data name="expo_ch6.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch6.TabIndex" type="System.Int32, mscorlib">
<value>41</value>
</data>
<data name="expo_ch6.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch6.Name" xml:space="preserve">
<value>expo_ch6</value>
</data>
<data name="&gt;&gt;expo_ch6.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch6.ZOrder" xml:space="preserve">
<value>15</value>
</data>
<data name="CMB_CH6.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH6.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH6.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH6.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH6.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 205</value>
</data>
<data name="CMB_CH6.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH6.TabIndex" type="System.Int32, mscorlib">
<value>39</value>
</data>
<data name="&gt;&gt;CMB_CH6.Name" xml:space="preserve">
<value>CMB_CH6</value>
</data>
<data name="&gt;&gt;CMB_CH6.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH6.ZOrder" xml:space="preserve">
<value>17</value>
</data>
<data name="revCH7.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH7.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH7.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 237</value>
</data>
<data name="revCH7.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH7.TabIndex" type="System.Int32, mscorlib">
<value>49</value>
</data>
<data name="&gt;&gt;revCH7.Name" xml:space="preserve">
<value>revCH7</value>
</data>
<data name="&gt;&gt;revCH7.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH7.ZOrder" xml:space="preserve">
<value>7</value>
</data>
<data name="label12.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label12.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label12.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 239</value>
</data>
<data name="label12.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label12.TabIndex" type="System.Int32, mscorlib">
<value>48</value>
</data>
<data name="label12.Text" xml:space="preserve">
<value>CH 7</value>
</data>
<data name="&gt;&gt;label12.Name" xml:space="preserve">
<value>label12</value>
</data>
<data name="&gt;&gt;label12.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label12.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label12.ZOrder" xml:space="preserve">
<value>8</value>
</data>
<data name="expo_ch7.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 238</value>
</data>
<data name="expo_ch7.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch7.TabIndex" type="System.Int32, mscorlib">
<value>47</value>
</data>
<data name="expo_ch7.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch7.Name" xml:space="preserve">
<value>expo_ch7</value>
</data>
<data name="&gt;&gt;expo_ch7.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch7.ZOrder" xml:space="preserve">
<value>9</value>
</data>
<data name="CMB_CH7.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH7.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH7.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH7.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH7.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 234</value>
</data>
<data name="CMB_CH7.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH7.TabIndex" type="System.Int32, mscorlib">
<value>45</value>
</data>
<data name="&gt;&gt;CMB_CH7.Name" xml:space="preserve">
<value>CMB_CH7</value>
</data>
<data name="&gt;&gt;CMB_CH7.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH7.ZOrder" xml:space="preserve">
<value>11</value>
</data>
<data name="revCH8.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="revCH8.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="revCH8.Location" type="System.Drawing.Point, System.Drawing">
<value>413, 266</value>
</data>
<data name="revCH8.Size" type="System.Drawing.Size, System.Drawing">
<value>15, 14</value>
</data>
<data name="revCH8.TabIndex" type="System.Int32, mscorlib">
<value>55</value>
</data>
<data name="&gt;&gt;revCH8.Name" xml:space="preserve">
<value>revCH8</value>
</data>
<data name="&gt;&gt;revCH8.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;revCH8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;revCH8.ZOrder" xml:space="preserve">
<value>1</value>
</data>
<data name="label13.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
</data>
<data name="label13.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="label13.Location" type="System.Drawing.Point, System.Drawing">
<value>9, 268</value>
</data>
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
<value>31, 13</value>
</data>
<data name="label13.TabIndex" type="System.Int32, mscorlib">
<value>54</value>
</data>
<data name="label13.Text" xml:space="preserve">
<value>CH 8</value>
</data>
<data name="&gt;&gt;label13.Name" xml:space="preserve">
<value>label13</value>
</data>
<data name="&gt;&gt;label13.Type" xml:space="preserve">
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;label13.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;label13.ZOrder" xml:space="preserve">
<value>2</value>
</data>
<data name="expo_ch8.Location" type="System.Drawing.Point, System.Drawing">
<value>307, 267</value>
</data>
<data name="expo_ch8.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 13</value>
</data>
<data name="expo_ch8.TabIndex" type="System.Int32, mscorlib">
<value>53</value>
</data>
<data name="expo_ch8.Text" xml:space="preserve">
<value>0</value>
</data>
<data name="&gt;&gt;expo_ch8.Name" xml:space="preserve">
<value>expo_ch8</value>
</data>
<data name="&gt;&gt;expo_ch8.Type" xml:space="preserve">
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;expo_ch8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;expo_ch8.ZOrder" xml:space="preserve">
<value>3</value>
</data>
<data name="CMB_CH8.Items" xml:space="preserve">
<value>RZ</value>
</data>
<data name="CMB_CH8.Items1" xml:space="preserve">
<value>X</value>
</data>
<data name="CMB_CH8.Items2" xml:space="preserve">
<value>Y</value>
</data>
<data name="CMB_CH8.Items3" xml:space="preserve">
<value>SL1</value>
</data>
<data name="CMB_CH8.Location" type="System.Drawing.Point, System.Drawing">
<value>72, 263</value>
</data>
<data name="CMB_CH8.Size" type="System.Drawing.Size, System.Drawing">
<value>70, 21</value>
</data>
<data name="CMB_CH8.TabIndex" type="System.Int32, mscorlib">
<value>51</value>
</data>
<data name="&gt;&gt;CMB_CH8.Name" xml:space="preserve">
<value>CMB_CH8</value>
</data>
<data name="&gt;&gt;CMB_CH8.Type" xml:space="preserve">
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</data>
<data name="&gt;&gt;CMB_CH8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CMB_CH8.ZOrder" xml:space="preserve">
<value>5</value>
</data>
<data name="BUT_detch8.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_detch8.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 263</value>
</data>
<data name="BUT_detch8.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="BUT_detch8.TabIndex" type="System.Int32, mscorlib">
<value>56</value>
</data>
<data name="BUT_detch8.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;BUT_detch8.Name" xml:space="preserve">
<value>BUT_detch8</value>
</data>
<data name="&gt;&gt;BUT_detch8.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch8.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch8.ZOrder" xml:space="preserve">
<value>0</value>
</data>
<data name="horizontalProgressBar4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar4.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 262</value>
</data>
<data name="horizontalProgressBar4.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar4.TabIndex" type="System.Int32, mscorlib">
<value>52</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.Name" xml:space="preserve">
<value>horizontalProgressBar4</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar4.ZOrder" xml:space="preserve">
<value>4</value>
</data>
<data name="BUT_detch4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
@ -778,7 +1315,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch4.ZOrder" xml:space="preserve">
<value>1</value>
<value>25</value>
</data>
<data name="BUT_detch3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -805,7 +1342,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch3.ZOrder" xml:space="preserve">
<value>2</value>
<value>26</value>
</data>
<data name="BUT_detch2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -832,7 +1369,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch2.ZOrder" xml:space="preserve">
<value>3</value>
<value>27</value>
</data>
<data name="BUT_detch1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -859,7 +1396,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch1.ZOrder" xml:space="preserve">
<value>4</value>
<value>28</value>
</data>
<data name="BUT_enable.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -886,7 +1423,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_enable.ZOrder" xml:space="preserve">
<value>10</value>
<value>34</value>
</data>
<data name="BUT_save.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -913,7 +1450,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_save.ZOrder" xml:space="preserve">
<value>11</value>
<value>35</value>
</data>
<data name="progressBar4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -937,7 +1474,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar4.ZOrder" xml:space="preserve">
<value>24</value>
<value>48</value>
</data>
<data name="progressBar3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -961,7 +1498,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar3.ZOrder" xml:space="preserve">
<value>25</value>
<value>49</value>
</data>
<data name="progressBar2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -985,7 +1522,7 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar2.ZOrder" xml:space="preserve">
<value>26</value>
<value>50</value>
</data>
<data name="progressBar1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
@ -1009,34 +1546,160 @@
<value>$this</value>
</data>
<data name="&gt;&gt;progressBar1.ZOrder" xml:space="preserve">
<value>27</value>
<value>51</value>
</data>
<data name="CHK_elevons.AutoSize" type="System.Boolean, mscorlib">
<value>True</value>
<data name="BUT_detch5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="CHK_elevons.Location" type="System.Drawing.Point, System.Drawing">
<value>434, 81</value>
<data name="BUT_detch5.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 176</value>
</data>
<data name="CHK_elevons.Size" type="System.Drawing.Size, System.Drawing">
<value>64, 17</value>
<data name="BUT_detch5.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="CHK_elevons.TabIndex" type="System.Int32, mscorlib">
<value>32</value>
<data name="BUT_detch5.TabIndex" type="System.Int32, mscorlib">
<value>38</value>
</data>
<data name="CHK_elevons.Text" xml:space="preserve">
<value>Elevons</value>
<data name="BUT_detch5.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;CHK_elevons.Name" xml:space="preserve">
<value>CHK_elevons</value>
<data name="&gt;&gt;BUT_detch5.Name" xml:space="preserve">
<value>BUT_detch5</value>
</data>
<data name="&gt;&gt;CHK_elevons.Type" xml:space="preserve">
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
<data name="&gt;&gt;BUT_detch5.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;CHK_elevons.Parent" xml:space="preserve">
<data name="&gt;&gt;BUT_detch5.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;CHK_elevons.ZOrder" xml:space="preserve">
<value>0</value>
<data name="&gt;&gt;BUT_detch5.ZOrder" xml:space="preserve">
<value>18</value>
</data>
<data name="horizontalProgressBar1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar1.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 175</value>
</data>
<data name="horizontalProgressBar1.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar1.TabIndex" type="System.Int32, mscorlib">
<value>34</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.Name" xml:space="preserve">
<value>horizontalProgressBar1</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar1.ZOrder" xml:space="preserve">
<value>22</value>
</data>
<data name="BUT_detch6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_detch6.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 205</value>
</data>
<data name="BUT_detch6.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="BUT_detch6.TabIndex" type="System.Int32, mscorlib">
<value>44</value>
</data>
<data name="BUT_detch6.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;BUT_detch6.Name" xml:space="preserve">
<value>BUT_detch6</value>
</data>
<data name="&gt;&gt;BUT_detch6.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch6.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch6.ZOrder" xml:space="preserve">
<value>12</value>
</data>
<data name="horizontalProgressBar2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar2.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 204</value>
</data>
<data name="horizontalProgressBar2.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar2.TabIndex" type="System.Int32, mscorlib">
<value>40</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.Name" xml:space="preserve">
<value>horizontalProgressBar2</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar2.ZOrder" xml:space="preserve">
<value>16</value>
</data>
<data name="BUT_detch7.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="BUT_detch7.Location" type="System.Drawing.Point, System.Drawing">
<value>148, 234</value>
</data>
<data name="BUT_detch7.Size" type="System.Drawing.Size, System.Drawing">
<value>45, 23</value>
</data>
<data name="BUT_detch7.TabIndex" type="System.Int32, mscorlib">
<value>50</value>
</data>
<data name="BUT_detch7.Text" xml:space="preserve">
<value>Auto Detect</value>
</data>
<data name="&gt;&gt;BUT_detch7.Name" xml:space="preserve">
<value>BUT_detch7</value>
</data>
<data name="&gt;&gt;BUT_detch7.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch7.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;BUT_detch7.ZOrder" xml:space="preserve">
<value>6</value>
</data>
<data name="horizontalProgressBar3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value>
</data>
<data name="horizontalProgressBar3.Location" type="System.Drawing.Point, System.Drawing">
<value>199, 233</value>
</data>
<data name="horizontalProgressBar3.Size" type="System.Drawing.Size, System.Drawing">
<value>100, 23</value>
</data>
<data name="horizontalProgressBar3.TabIndex" type="System.Int32, mscorlib">
<value>46</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.Name" xml:space="preserve">
<value>horizontalProgressBar3</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.Type" xml:space="preserve">
<value>ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.Parent" xml:space="preserve">
<value>$this</value>
</data>
<data name="&gt;&gt;horizontalProgressBar3.ZOrder" xml:space="preserve">
<value>10</value>
</data>
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
<value>True</value>
@ -1045,7 +1708,7 @@
<value>6, 13</value>
</data>
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
<value>498, 220</value>
<value>498, 331</value>
</data>
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>

View File

@ -13,203 +13,146 @@
namespace apo {
class ControllerPlane: public AP_Controller {
private:
AP_Var_group _group;
AP_Var_group _trimGroup;
AP_Uint8 _mode;
AP_Uint8 _rdrAilMix;
bool _needsTrim;
AP_Float _ailTrim;
AP_Float _elvTrim;
AP_Float _rdrTrim;
AP_Float _thrTrim;
enum {
ch_mode = 0, ch_roll, ch_pitch, ch_thr, ch_yaw
};
enum {
k_chMode = k_radioChannelsStart,
k_chRoll,
k_chPitch,
k_chYaw,
k_chThr,
k_pidBnkRll = k_controllersStart,
k_pidSpdPit,
k_pidPitPit,
k_pidYwrYaw,
k_pidHdgBnk,
k_pidAltThr,
k_trim = k_customStart
};
BlockPID pidBnkRll; // bank error to roll servo deflection
BlockPID pidSpdPit; // speed error to pitch command
BlockPID pidPitPit; // pitch error to pitch servo deflection
BlockPID pidYwrYaw; // yaw rate error to yaw servo deflection
BlockPID pidHdgBnk; // heading error to bank command
BlockPID pidAltThr; // altitude error to throttle deflection
bool requireRadio;
public:
ControllerPlane(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
_group(k_cntrl, PSTR("cntrl_")),
_trimGroup(k_trim, PSTR("trim_")),
_mode(&_group, 1, MAV_MODE_UNINIT, PSTR("mode")),
_rdrAilMix(&_group, 2, rdrAilMix, PSTR("rdrAilMix")),
_needsTrim(false),
_ailTrim(&_trimGroup, 1, ailTrim, PSTR("ail")),
_elvTrim(&_trimGroup, 2, elvTrim, PSTR("elv")),
_rdrTrim(&_trimGroup, 3, rdrTrim, PSTR("rdr")),
_thrTrim(&_trimGroup, 4, thrTrim, PSTR("thr")),
pidBnkRll(new AP_Var_group(k_pidBnkRll, PSTR("bnkRll_")), 1,
pidBnkRllP, pidBnkRllI, pidBnkRllD, pidBnkRllAwu,
pidBnkRllLim, pidBnkRllDFCut),
pidPitPit(new AP_Var_group(k_pidPitPit, PSTR("pitPit_")), 1,
pidPitPitP, pidPitPitI, pidPitPitD, pidPitPitAwu,
pidPitPitLim, pidPitPitDFCut),
pidSpdPit(new AP_Var_group(k_pidSpdPit, PSTR("spdPit_")), 1,
pidSpdPitP, pidSpdPitI, pidSpdPitD, pidSpdPitAwu,
pidSpdPitLim, pidSpdPitDFCut),
pidYwrYaw(new AP_Var_group(k_pidYwrYaw, PSTR("ywrYaw_")), 1,
pidYwrYawP, pidYwrYawI, pidYwrYawD, pidYwrYawAwu,
pidYwrYawLim, pidYwrYawDFCut),
pidHdgBnk(new AP_Var_group(k_pidHdgBnk, PSTR("hdgBnk_")), 1,
pidHdgBnkP, pidHdgBnkI, pidHdgBnkD, pidHdgBnkAwu,
pidHdgBnkLim, pidHdgBnkDFCut),
pidAltThr(new AP_Var_group(k_pidAltThr, PSTR("altThr_")), 1,
pidAltThrP, pidAltThrI, pidAltThrD, pidAltThrAwu,
pidAltThrLim, pidAltThrDFCut),
requireRadio(false) {
ControllerPlane(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal, new AP_ArmingMechanism(hal,ch_thrust,ch_yaw,0.1,-0.9,0.9),ch_mode),
_trimGroup(k_trim, PSTR("trim_")),
_rdrAilMix(&_group, 2, rdrAilMix, PSTR("rdrAilMix")),
_needsTrim(false),
_ailTrim(&_trimGroup, 1, ailTrim, PSTR("ail")),
_elvTrim(&_trimGroup, 2, elvTrim, PSTR("elv")),
_rdrTrim(&_trimGroup, 3, rdrTrim, PSTR("rdr")),
_thrTrim(&_trimGroup, 4, thrTrim, PSTR("thr")),
pidBnkRll(new AP_Var_group(k_pidBnkRll, PSTR("bnkRll_")), 1,
pidBnkRllP, pidBnkRllI, pidBnkRllD, pidBnkRllAwu,
pidBnkRllLim, pidBnkRllDFCut),
pidPitPit(new AP_Var_group(k_pidPitPit, PSTR("pitPit_")), 1,
pidPitPitP, pidPitPitI, pidPitPitD, pidPitPitAwu,
pidPitPitLim, pidPitPitDFCut),
pidSpdPit(new AP_Var_group(k_pidSpdPit, PSTR("spdPit_")), 1,
pidSpdPitP, pidSpdPitI, pidSpdPitD, pidSpdPitAwu,
pidSpdPitLim, pidSpdPitDFCut),
pidYwrYaw(new AP_Var_group(k_pidYwrYaw, PSTR("ywrYaw_")), 1,
pidYwrYawP, pidYwrYawI, pidYwrYawD, pidYwrYawAwu,
pidYwrYawLim, pidYwrYawDFCut),
pidHdgBnk(new AP_Var_group(k_pidHdgBnk, PSTR("hdgBnk_")), 1,
pidHdgBnkP, pidHdgBnkI, pidHdgBnkD, pidHdgBnkAwu,
pidHdgBnkLim, pidHdgBnkDFCut),
pidAltThr(new AP_Var_group(k_pidAltThr, PSTR("altThr_")), 1,
pidAltThrP, pidAltThrI, pidAltThrD, pidAltThrAwu,
pidAltThrLim, pidAltThrDFCut),
requireRadio(false), _aileron(0), _elevator(0), _rudder(0), _throttle(0) {
_hal->debug->println_P(PSTR("initializing plane controller"));
_hal->debug->println_P(PSTR("initializing plane controller"));
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("mode_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRoll, PSTR("roll_"), APM_RC, 0, 1200,
1500, 1800, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chPitch, PSTR("pitch_"), APM_RC, 1, 1200,
1500, 1800, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("thr_"), APM_RC, 2, 1100, 1100,
1900, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chYaw, PSTR("yaw_"), APM_RC, 3, 1200, 1500,
1800, RC_MODE_INOUT, false));
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
virtual void update(const float & dt) {
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("mode_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRoll, PSTR("roll_"), APM_RC, 0, 1200,
1500, 1800, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chPitch, PSTR("pitch_"), APM_RC, 1, 1200,
1500, 1800, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("thr_"), APM_RC, 2, 1100, 1100,
1900, RC_MODE_INOUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chYaw, PSTR("yaw_"), APM_RC, 3, 1200, 1500,
1800, RC_MODE_INOUT, false));
}
// check for heartbeat
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n"));
return;
// if the value of the throttle is less than 5% cut motor power
} else if (requireRadio && _hal->rc[ch_thr]->getRadioPosition() < 0.05) {
_mode = MAV_MODE_LOCKED;
setAllRadioChannelsToNeutral();
_hal->setState(MAV_STATE_STANDBY);
return;
// if in live mode then set state to active
} else if (_hal->getMode() == MODE_LIVE) {
_hal->setState(MAV_STATE_ACTIVE);
// if in hardware in the loop (control) mode, set to hilsim
} else if (_hal->getMode() == MODE_HIL_CNTL) {
_hal->setState(MAV_STATE_HILSIM);
}
private:
// methdos
void manualLoop(const float dt) {
setAllRadioChannelsManually();
// force auto to read new manual trim
if (_needsTrim == false)
_needsTrim = true;
}
void autoLoop(const float dt) {
_aileron = pidBnkRll.update(
pidHdgBnk.update(_guide->getHeadingError(), dt) - _nav->getRoll(), dt);
_elevator = pidPitPit.update(
-pidSpdPit.update(
_guide->getAirSpeedCommand() - _nav->getAirSpeed(),
dt) - _nav->getPitch(), dt);
_rudder = pidYwrYaw.update(-_nav->getYawRate(), dt);
// read switch to set mode
if (_hal->rc[ch_mode]->getRadioPosition() > 0) {
_mode = MAV_MODE_MANUAL;
} else {
_mode = MAV_MODE_AUTO;
}
// desired yaw rate is zero, needs washout
_throttle = pidAltThr.update(
_guide->getAltitudeCommand() - _nav->getAlt(), dt);
// manual mode
switch (_mode) {
if (_needsTrim) {
// need to subtract current controller deflections so control
// surfaces are actually at the same position as manual flight
_ailTrim = _hal->rc[ch_roll]->getRadioPosition() - _aileron;
_elvTrim = _hal->rc[ch_pitch]->getRadioPosition() - _elevator;
_rdrTrim = _hal->rc[ch_yaw]->getRadioPosition() - _rudder;
_thrTrim = _hal->rc[ch_thrust]->getRadioPosition() - _throttle;
_needsTrim = false;
}
case MAV_MODE_MANUAL: {
setAllRadioChannelsManually();
// actuator mixing/ output
_aileron += _rdrAilMix * _rudder + _ailTrim;
_elevator += _elvTrim;
_rudder += _rdrTrim;
_throttle += _thrTrim;
}
void setMotorsActive() {
// turn all motors off if below 0.1 throttle
if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) {
setAllRadioChannelsToNeutral();
} else {
_hal->rc[ch_roll]->setPosition(_aileron);
_hal->rc[ch_yaw]->setPosition(_rudder);
_hal->rc[ch_pitch]->setPosition(_elevator);
_hal->rc[ch_thrust]->setPosition(_throttle);
}
}
// force auto to read new manual trim
if (_needsTrim == false)
_needsTrim = true;
//_hal->debug->println("manual");
break;
}
case MAV_MODE_AUTO: {
float headingError = _guide->getHeadingCommand()
- _nav->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
// attributes
enum {
ch_mode = 0, ch_roll, ch_pitch, ch_thrust, ch_yaw
};
enum {
k_chMode = k_radioChannelsStart,
k_chRoll,
k_chPitch,
k_chYaw,
k_chThr,
float aileron = pidBnkRll.update(
pidHdgBnk.update(headingError, dt) - _nav->getRoll(), dt);
float elevator = pidPitPit.update(
-pidSpdPit.update(
_guide->getAirSpeedCommand() - _nav->getAirSpeed(),
dt) - _nav->getPitch(), dt);
float rudder = pidYwrYaw.update(-_nav->getYawRate(), dt);
// desired yaw rate is zero, needs washout
float throttle = pidAltThr.update(
_guide->getAltitudeCommand() - _nav->getAlt(), dt);
k_pidBnkRll = k_controllersStart,
k_pidSpdPit,
k_pidPitPit,
k_pidYwrYaw,
k_pidHdgBnk,
k_pidAltThr,
// if needs trim
if (_needsTrim) {
// need to subtract current controller deflections so control
// surfaces are actually at the same position as manual flight
_ailTrim = _hal->rc[ch_roll]->getRadioPosition() - aileron;
_elvTrim = _hal->rc[ch_pitch]->getRadioPosition() - elevator;
_rdrTrim = _hal->rc[ch_yaw]->getRadioPosition() - rudder;
_thrTrim = _hal->rc[ch_thr]->getRadioPosition() - throttle;
_needsTrim = false;
}
// actuator mixing/ output
_hal->rc[ch_roll]->setPosition(
aileron + _rdrAilMix * rudder + _ailTrim);
_hal->rc[ch_yaw]->setPosition(rudder + _rdrTrim);
_hal->rc[ch_pitch]->setPosition(elevator + _elvTrim);
_hal->rc[ch_thr]->setPosition(throttle + _thrTrim);
//_hal->debug->println("automode");
// heading debug
// Serial.print("heading command: "); Serial.println(_guide->getHeadingCommand());
// Serial.print("heading: "); Serial.println(_nav->getYaw());
// Serial.print("heading error: "); Serial.println(headingError);
// alt debug
// Serial.print("alt command: "); Serial.println(_guide->getAltitudeCommand());
// Serial.print("alt: "); Serial.println(_nav->getAlt());
// Serial.print("alt error: "); Serial.println(_guide->getAltitudeCommand() - _nav->getAlt());
break;
}
default: {
setAllRadioChannelsToNeutral();
_mode = MAV_MODE_FAILSAFE;
_hal->setState(MAV_STATE_EMERGENCY);
_hal->debug->printf_P(PSTR("unknown controller mode\n"));
break;
}
}
}
k_trim = k_customStart
};
AP_Var_group _trimGroup;
AP_Uint8 _rdrAilMix;
bool _needsTrim;
AP_Float _ailTrim;
AP_Float _elvTrim;
AP_Float _rdrTrim;
AP_Float _thrTrim;
BlockPID pidBnkRll; // bank error to roll servo deflection
BlockPID pidSpdPit; // speed error to pitch command
BlockPID pidPitPit; // pitch error to pitch servo deflection
BlockPID pidYwrYaw; // yaw rate error to yaw servo deflection
BlockPID pidHdgBnk; // heading error to bank command
BlockPID pidAltThr; // altitude error to throttle deflection
bool requireRadio;
float _aileron;
float _elevator;
float _rudder;
float _throttle;
};
} // namespace apo
#endif /* CONTROLLERPLANE_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -10,310 +10,179 @@
#include "../APO/AP_Controller.h"
#include "../APO/AP_BatteryMonitor.h"
#include "../APO/AP_ArmingMechanism.h"
namespace apo {
class ControllerQuad: public AP_Controller {
public:
ControllerQuad(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal, new AP_ArmingMechanism(hal,ch_thrust,ch_yaw,0.1,-0.9,0.9), ch_mode),
pidRoll(new AP_Var_group(k_pidRoll, PSTR("ROLL_")), 1,
PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU,
PID_ATT_LIM, PID_ATT_DFCUT),
pidPitch(new AP_Var_group(k_pidPitch, PSTR("PITCH_")), 1,
PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU,
PID_ATT_LIM, PID_ATT_DFCUT),
pidYaw(new AP_Var_group(k_pidYaw, PSTR("YAW_")), 1,
PID_YAWPOS_P, PID_YAWPOS_I, PID_YAWPOS_D,
PID_YAWPOS_AWU, PID_YAWPOS_LIM, PID_ATT_DFCUT),
pidYawRate(new AP_Var_group(k_pidYawRate, PSTR("YAWRT_")), 1,
PID_YAWSPEED_P, PID_YAWSPEED_I, PID_YAWSPEED_D,
PID_YAWSPEED_AWU, PID_YAWSPEED_LIM, PID_YAWSPEED_DFCUT),
pidPN(new AP_Var_group(k_pidPN, PSTR("NORTH_")), 1, PID_POS_P,
PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT),
pidPE(new AP_Var_group(k_pidPE, PSTR("EAST_")), 1, PID_POS_P,
PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT),
pidPD(new AP_Var_group(k_pidPD, PSTR("DOWN_")), 1, PID_POS_Z_P,
PID_POS_Z_I, PID_POS_Z_D, PID_POS_Z_AWU, PID_POS_Z_LIM, PID_POS_DFCUT),
_thrustMix(0), _pitchMix(0), _rollMix(0), _yawMix(0),
_cmdRoll(0), _cmdPitch(0), _cmdYawRate(0) {
_hal->debug->println_P(PSTR("initializing quad controller"));
/**
* note that these are not the controller radio channel numbers, they are just
* unique keys so they can be reaccessed from the hal rc vector
*/
enum {
CH_MODE = 0, // note scicoslab channels set mode, left, right, front, back order
CH_RIGHT,
CH_LEFT,
CH_FRONT,
CH_BACK,
CH_ROLL,
CH_PITCH,
CH_THRUST,
CH_YAW
};
/*
* allocate radio channels
* the order of the channels has to match the enumeration above
*/
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 0, 1100,
1100, 1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 1, 1100,
1100, 1900, RC_MODE_OUT, false));
// must match channel enum
enum {
k_chMode = k_radioChannelsStart,
k_chRight,
k_chLeft,
k_chFront,
k_chBack,
k_chRoll,
k_chPitch,
k_chThr,
k_chYaw
};
enum {
k_pidGroundSpeed2Throttle = k_controllersStart,
k_pidStr,
k_pidPN,
k_pidPE,
k_pidPD,
k_pidRoll,
k_pidPitch,
k_pidYawRate,
k_pidYaw,
};
ControllerQuad(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
AP_Controller(nav, guide, hal),
pidRoll(new AP_Var_group(k_pidRoll, PSTR("ROLL_")), 1,
PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU,
PID_ATT_LIM, PID_ATT_DFCUT),
pidPitch(new AP_Var_group(k_pidPitch, PSTR("PITCH_")), 1,
PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU,
PID_ATT_LIM, PID_ATT_DFCUT),
pidYaw(new AP_Var_group(k_pidYaw, PSTR("YAW_")), 1,
PID_YAWPOS_P, PID_YAWPOS_I, PID_YAWPOS_D,
PID_YAWPOS_AWU, PID_YAWPOS_LIM, PID_ATT_DFCUT),
pidYawRate(new AP_Var_group(k_pidYawRate, PSTR("YAWRT_")), 1,
PID_YAWSPEED_P, PID_YAWSPEED_I, PID_YAWSPEED_D,
PID_YAWSPEED_AWU, PID_YAWSPEED_LIM, PID_YAWSPEED_DFCUT),
pidPN(new AP_Var_group(k_pidPN, PSTR("NORTH_")), 1, PID_POS_P,
PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT),
pidPE(new AP_Var_group(k_pidPE, PSTR("EAST_")), 1, PID_POS_P,
PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT),
pidPD(new AP_Var_group(k_pidPD, PSTR("DOWN_")), 1, PID_POS_Z_P,
PID_POS_Z_I, PID_POS_Z_D, PID_POS_Z_AWU, PID_POS_Z_LIM, PID_POS_DFCUT),
_armingClock(0), _thrustMix(0), _pitchMix(0), _rollMix(0), _yawMix(0),
_cmdRoll(0), _cmdPitch(0), _cmdYawRate(0), _mode(MAV_MODE_LOCKED) {
/*
* allocate radio channels
* the order of the channels has to match the enumeration above
*/
_hal->rc.push_back(
new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 0, 1100,
1100, 1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 1, 1100,
1100, 1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chFront, PSTR("FRONT_"), APM_RC, 2, 1100,
1100, 1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chBack, PSTR("BACK_"), APM_RC, 3, 1100,
1100, 1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRoll, PSTR("ROLL_"), APM_RC, 0, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chPitch, PSTR("PITCH_"), APM_RC, 1, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THRUST_"), APM_RC, 2, 1100,
1100, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chYaw, PSTR("YAW_"), APM_RC, 3, 1100, 1500,
1900, RC_MODE_IN, false));
}
virtual void update(const float & dt) {
//_hal->debug->printf_P(PSTR("thr: %f, yaw: %f\n"),_hal->rc[CH_THRUST]->getRadioPosition(),_hal->rc[CH_YAW]->getRadioPosition());
// arming
//
// to arm: put stick to bottom right for 100 controller cycles
// (max yaw, min throttle)
//
// didn't use clock here in case of millis() roll over
// for long runs
if ( (_hal->getState() != MAV_STATE_ACTIVE) &
(_hal->rc[CH_THRUST]->getRadioPosition() < 0.1) &&
(_hal->rc[CH_YAW]->getRadioPosition() < -0.9) ) {
// always start clock at 0
if (_armingClock<0) _armingClock = 0;
if (_armingClock++ >= 100) {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed"));
_hal->setState(MAV_STATE_ACTIVE);
} else {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("arming"));
}
}
// disarming
//
// to disarm: put stick to bottom left for 100 controller cycles
// (min yaw, min throttle)
else if ( (_hal->getState() == MAV_STATE_ACTIVE) &
(_hal->rc[CH_THRUST]->getRadioPosition() < 0.1) &&
(_hal->rc[CH_YAW]->getRadioPosition() > 0.9) ) {
// always start clock at 0
if (_armingClock>0) _armingClock = 0;
if (_armingClock-- <= -100) {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed"));
_hal->setState(MAV_STATE_STANDBY);
} else {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarming"));
}
}
// reset arming clock and report status
else if (_armingClock != 0) {
_armingClock = 0;
if (_hal->getState()==MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed"));
else if (_hal->getState()!=MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed"));
}
// determine flight mode
//
// check for heartbeat from gcs, if not found go to failsafe
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("configure gcs to send heartbeat"));
// if battery less than 5%, go to failsafe
} else if (_hal->batteryMonitor->getPercentage() < 5) {
_mode = MAV_MODE_FAILSAFE;
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("recharge battery"));
// manual/auto switch
} else {
// if all emergencies cleared, fall back to standby
if (_hal->getState()==MAV_STATE_EMERGENCY) _hal->setState(MAV_STATE_STANDBY);
if (_hal->rc[CH_MODE]->getRadioPosition() > 0) _mode = MAV_MODE_MANUAL;
else _mode = MAV_MODE_AUTO;
}
// handle flight modes
switch(_mode) {
case MAV_MODE_LOCKED: {
_hal->setState(MAV_STATE_STANDBY);
break;
}
case MAV_MODE_FAILSAFE: {
_hal->setState(MAV_STATE_EMERGENCY);
break;
}
case MAV_MODE_MANUAL: {
manualPositionLoop();
autoAttitudeLoop(dt);
break;
}
case MAV_MODE_AUTO: {
// until position loop is tested just
// go to standby
_hal->setState(MAV_STATE_STANDBY);
//attitudeLoop();
// XXX autoPositionLoop NOT TESTED, don't uncomment yet
//autoPositionLoop(dt);
//autoAttitudeLoop(dt);
break;
}
default: {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("unknown mode"));
_hal->setState(MAV_STATE_EMERGENCY);
}
}
// this sends commands to motors
setMotors();
}
virtual MAV_MODE getMode() {
return (MAV_MODE) _mode.get();
}
_hal->rc.push_back(
new AP_RcChannel(k_chFront, PSTR("FRONT_"), APM_RC, 2, 1100,
1100, 1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chBack, PSTR("BACK_"), APM_RC, 3, 1100,
1100, 1900, RC_MODE_OUT, false));
_hal->rc.push_back(
new AP_RcChannel(k_chRoll, PSTR("ROLL_"), APM_RC, 0, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chPitch, PSTR("PITCH_"), APM_RC, 1, 1100,
1500, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chThr, PSTR("THRUST_"), APM_RC, 2, 1100,
1100, 1900, RC_MODE_IN, false));
_hal->rc.push_back(
new AP_RcChannel(k_chYaw, PSTR("YAW_"), APM_RC, 3, 1100, 1500,
1900, RC_MODE_IN, false));
}
private:
// methods
void manualLoop(const float dt) {
setAllRadioChannelsManually();
_cmdRoll = -0.5 * _hal->rc[ch_roll]->getPosition();
_cmdPitch = -0.5 * _hal->rc[ch_pitch]->getPosition();
_cmdYawRate = -1 * _hal->rc[ch_yaw]->getPosition();
_thrustMix = _hal->rc[ch_thrust]->getPosition();
autoAttitudeLoop(dt);
}
void autoLoop(const float dt) {
autoPositionLoop(dt);
autoAttitudeLoop(dt);
AP_Uint8 _mode;
BlockPIDDfb pidRoll, pidPitch, pidYaw;
BlockPID pidYawRate;
BlockPIDDfb pidPN, pidPE, pidPD;
int32_t _armingClock;
// XXX currently auto loop not tested, so
// put vehicle in standby
_hal->setState(MAV_STATE_STANDBY);
}
void autoPositionLoop(float dt) {
float cmdNorthTilt = pidPN.update(_nav->getPN(),_nav->getVN(),dt);
float cmdEastTilt = pidPE.update(_nav->getPE(),_nav->getVE(),dt);
float cmdDown = pidPD.update(_nav->getPD(),_nav->getVD(),dt);
float _thrustMix, _pitchMix, _rollMix, _yawMix;
float _cmdRoll, _cmdPitch, _cmdYawRate;
// "transform-to-body"
{
float trigSin = sin(-_nav->getYaw());
float trigCos = cos(-_nav->getYaw());
_cmdPitch = cmdEastTilt * trigCos - cmdNorthTilt * trigSin;
_cmdRoll = -cmdEastTilt * trigSin + cmdNorthTilt * trigCos;
// note that the north tilt is negative of the pitch
}
_cmdYawRate = 0;
void manualPositionLoop() {
setAllRadioChannelsManually();
_cmdRoll = -0.5 * _hal->rc[CH_ROLL]->getPosition();
_cmdPitch = -0.5 * _hal->rc[CH_PITCH]->getPosition();
_cmdYawRate = -1 * _hal->rc[CH_YAW]->getPosition();
_thrustMix = _hal->rc[CH_THRUST]->getPosition();
}
_thrustMix = THRUST_HOVER_OFFSET + cmdDown;
void autoPositionLoop(float dt) {
float cmdNorthTilt = pidPN.update(_nav->getPN(),_nav->getVN(),dt);
float cmdEastTilt = pidPE.update(_nav->getPE(),_nav->getVE(),dt);
float cmdDown = pidPD.update(_nav->getPD(),_nav->getVD(),dt);
// "thrust-trim-adjust"
if (fabs(_cmdRoll) > 0.5) _thrustMix *= 1.13949393;
else _thrustMix /= cos(_cmdRoll);
// "transform-to-body"
{
float trigSin = sin(-_nav->getYaw());
float trigCos = cos(-_nav->getYaw());
_cmdPitch = cmdEastTilt * trigCos - cmdNorthTilt * trigSin;
_cmdRoll = -cmdEastTilt * trigSin + cmdNorthTilt * trigCos;
// note that the north tilt is negative of the pitch
}
_cmdYawRate = 0;
if (fabs(_cmdPitch) > 0.5) _thrustMix *= 1.13949393;
else _thrustMix /= cos(_cmdPitch);
}
void autoAttitudeLoop(float dt) {
_rollMix = pidRoll.update(_cmdRoll - _nav->getRoll(),
_nav->getRollRate(), dt);
_pitchMix = pidPitch.update(_cmdPitch - _nav->getPitch(),
_nav->getPitchRate(), dt);
_yawMix = pidYawRate.update(_cmdYawRate - _nav->getYawRate(), dt);
}
void setMotorsActive() {
// turn all motors off if below 0.1 throttle
if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) {
setAllRadioChannelsToNeutral();
} else {
_hal->rc[ch_right]->setPosition(_thrustMix - _rollMix + _yawMix);
_hal->rc[ch_left]->setPosition(_thrustMix + _rollMix + _yawMix);
_hal->rc[ch_front]->setPosition(_thrustMix + _pitchMix - _yawMix);
_hal->rc[ch_back]->setPosition(_thrustMix - _pitchMix - _yawMix);
}
}
_thrustMix = THRUST_HOVER_OFFSET + cmdDown;
// "thrust-trim-adjust"
if (fabs(_cmdRoll) > 0.5) _thrustMix *= 1.13949393;
else _thrustMix /= cos(_cmdRoll);
if (fabs(_cmdPitch) > 0.5) _thrustMix *= 1.13949393;
else _thrustMix /= cos(_cmdPitch);
}
void autoAttitudeLoop(float dt) {
_rollMix = pidRoll.update(_cmdRoll - _nav->getRoll(),
_nav->getRollRate(), dt);
_pitchMix = pidPitch.update(_cmdPitch - _nav->getPitch(),
_nav->getPitchRate(), dt);
_yawMix = pidYawRate.update(_cmdYawRate - _nav->getYawRate(), dt);
}
void setMotors() {
switch (_hal->getState()) {
case MAV_STATE_ACTIVE: {
digitalWrite(_hal->aLedPin, HIGH);
// turn all motors off if below 0.1 throttle
if (_hal->rc[CH_THRUST]->getRadioPosition() < 0.1) {
setAllRadioChannelsToNeutral();
} else {
_hal->rc[CH_RIGHT]->setPosition(_thrustMix - _rollMix + _yawMix);
_hal->rc[CH_LEFT]->setPosition(_thrustMix + _rollMix + _yawMix);
_hal->rc[CH_FRONT]->setPosition(_thrustMix + _pitchMix - _yawMix);
_hal->rc[CH_BACK]->setPosition(_thrustMix - _pitchMix - _yawMix);
}
break;
}
case MAV_STATE_EMERGENCY: {
digitalWrite(_hal->aLedPin, LOW);
setAllRadioChannelsToNeutral();
break;
}
case MAV_STATE_STANDBY: {
digitalWrite(_hal->aLedPin,LOW);
setAllRadioChannelsToNeutral();
break;
}
default: {
digitalWrite(_hal->aLedPin, LOW);
setAllRadioChannelsToNeutral();
}
}
}
// attributes
/**
* note that these are not the controller radio channel numbers, they are just
* unique keys so they can be reaccessed from the hal rc vector
*/
enum {
ch_mode = 0, // note scicoslab channels set mode, left, right, front, back order
ch_right,
ch_left,
ch_front,
ch_back,
ch_roll,
ch_pitch,
ch_thrust,
ch_yaw
};
// must match channel enum
enum {
k_chMode = k_radioChannelsStart,
k_chRight,
k_chLeft,
k_chFront,
k_chBack,
k_chRoll,
k_chPitch,
k_chThr,
k_chYaw
};
enum {
k_pidGroundSpeed2Throttle = k_controllersStart,
k_pidStr,
k_pidPN,
k_pidPE,
k_pidPD,
k_pidRoll,
k_pidPitch,
k_pidYawRate,
k_pidYaw,
};
BlockPIDDfb pidRoll, pidPitch, pidYaw;
BlockPID pidYawRate;
BlockPIDDfb pidPN, pidPE, pidPD;
float _thrustMix, _pitchMix, _rollMix, _yawMix;
float _cmdRoll, _cmdPitch, _cmdYawRate;
};
} // namespace apo
#endif /* CONTROLLERQUAD_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -11,7 +11,7 @@
// vehicle options
static const apo::vehicle_t vehicle = apo::VEHICLE_PLANE;
static const apo::halMode_t halMode = apo::MODE_LIVE;
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_2560;
static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_1280;
static const uint8_t heartBeatTimeout = 3;
// algorithm selection
@ -27,10 +27,10 @@ static const uint8_t heartBeatTimeout = 3;
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
// baud rates
static uint32_t debugBaud = 57600;
static uint32_t telemBaud = 57600;
static uint32_t gpsBaud = 38400;
static uint32_t hilBaud = 57600;
static const uint32_t debugBaud = 57600;
static const uint32_t telemBaud = 57600;
static const uint32_t gpsBaud = 38400;
static const uint32_t hilBaud = 57600;
// optional sensors
static const bool gpsEnabled = false;
@ -40,7 +40,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD
// compass orientation: See AP_Compass_HMC5843.h for possible values
// battery monitoring
static const bool batteryMonitorEnabled = true;
static const bool batteryMonitorEnabled = false;
static const uint8_t batteryPin = 0;
static const float batteryVoltageDivRatio = 6;
static const float batteryMinVolt = 10.0;
@ -117,6 +117,12 @@ static const float elvTrim = 0.0;
static const float rdrTrim = 0.0;
static const float thrTrim = 0.5;
// guidance
static const float velCmd = 1; // m/s
static const float xt = 10; // cross track gain
static const float xtLim = 90; // cross track angle limit, deg
#include "ControllerPlane.h"
#endif /* PLANEEASYSTAR_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -27,10 +27,10 @@ static const uint8_t heartBeatTimeout = 3;
#define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL
// baud rates
static uint32_t debugBaud = 57600;
static uint32_t telemBaud = 57600;
static uint32_t gpsBaud = 38400;
static uint32_t hilBaud = 57600;
static const uint32_t debugBaud = 57600;
static const uint32_t telemBaud = 57600;
static const uint32_t gpsBaud = 38400;
static const uint32_t hilBaud = 57600;
// optional sensors
static const bool gpsEnabled = false;
@ -54,7 +54,7 @@ static const bool rangeFinderUpEnabled = false;
static const bool rangeFinderDownEnabled = false;
// loop rates
static const float loopRate = 400; // attitude nav
static const float loopRate = 250; // attitude nav
static const float loop0Rate = 50; // controller
static const float loop1Rate = 10; // pos nav/ gcs fast
static const float loop2Rate = 1; // gcs slow
@ -91,9 +91,14 @@ static const float PID_YAWSPEED_D = 0;
static const float PID_YAWSPEED_LIM = .05; // 5 % motors
static const float PID_YAWSPEED_AWU = 0.0;
static const float PID_YAWSPEED_DFCUT = 3.0; // 3 Radians, about 1 Hz
static const float THRUST_HOVER_OFFSET = 0.475;
// guidance
static const float velCmd = 1; // m/s
static const float xt = 10; // cross track gain
static const float xtLim = 90; // cross track angle limit, deg
#include "ControllerQuad.h"
#endif /* QUADARDUCOPTER_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -17,8 +17,8 @@
#include <WProgram.h>
// Vehicle Configuration
#include "QuadArducopter.h"
//#include "PlaneEasystar.h"
//#include "QuadArducopter.h"
#include "PlaneEasystar.h"
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"

View File

@ -4,7 +4,7 @@
#define TEMP_FILTER_SIZE 16
#define PRESS_FILTER_SIZE 10
#include <APM_BMP085_hil.h>
#include "APM_BMP085_hil.h"
class APM_BMP085_Class
{

View File

@ -16,6 +16,10 @@
#include "AP_Navigator.h"
#include "AP_RcChannel.h"
#include "AP_BatteryMonitor.h"
//#include "AP_Var_keys.h"
#include "AP_ArmingMechanism.h"
#include "AP_CommLink.h"
#include "AP_Var_keys.h"
#include "constants.h"
#endif /* APO_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -14,168 +14,171 @@ static apo::AP_Autopilot * autoPilot;
void setup() {
using namespace apo;
AP_Var::load_all();
using namespace apo;
// Declare all parts of the system
AP_Navigator * navigator = NULL;
AP_Guide * guide = NULL;
AP_Controller * controller = NULL;
AP_HardwareAbstractionLayer * hal = NULL;
AP_Var::load_all();
/*
* Communications
*/
Serial.begin(debugBaud, 128, 128); // debug
// hardware abstraction layer
hal = new AP_HardwareAbstractionLayer(
halMode, board, vehicle, heartBeatTimeout);
// debug serial
hal->debug = &Serial;
hal->debug->println_P(PSTR("initializing debug line"));
// Declare all parts of the system
AP_Navigator * navigator = NULL;
AP_Guide * guide = NULL;
AP_Controller * controller = NULL;
AP_HardwareAbstractionLayer * hal = NULL;
/*
* Sensor initialization
*/
if (hal->getMode() == MODE_LIVE) {
/*
* Communications
*/
Serial.begin(debugBaud, 128, 128); // debug
hal->debug->println_P(PSTR("initializing adc"));
hal->adc = new ADC_CLASS;
hal->adc->Init();
// hardware abstraction layer
hal = new AP_HardwareAbstractionLayer(
halMode, board, vehicle, heartBeatTimeout);
if (batteryMonitorEnabled) {
hal->batteryMonitor = new AP_BatteryMonitor(batteryPin,batteryVoltageDivRatio,batteryMinVolt,batteryMaxVolt);
}
// debug serial
hal->debug = &Serial;
hal->debug->println_P(PSTR("initializing debug line"));
if (gpsEnabled) {
Serial1.begin(gpsBaud, 128, 16); // gps
hal->debug->println_P(PSTR("initializing gps"));
AP_GPS_Auto gpsDriver(&Serial1, &(hal->gps));
hal->gps = &gpsDriver;
hal->gps->callback = delay;
hal->gps->init();
}
/*
* Sensor initialization
*/
if (hal->getMode() == MODE_LIVE) {
if (baroEnabled) {
hal->debug->println_P(PSTR("initializing baro"));
hal->baro = new BARO_CLASS;
hal->baro->Init();
}
hal->debug->println_P(PSTR("initializing adc"));
hal->adc = new ADC_CLASS;
hal->adc->Init();
if (compassEnabled) {
Wire.begin();
hal->debug->println_P(PSTR("initializing compass"));
hal->compass = new COMPASS_CLASS;
hal->compass->set_orientation(compassOrientation);
hal->compass->set_offsets(0,0,0);
hal->compass->set_declination(0.0);
hal->compass->init();
}
if (batteryMonitorEnabled) {
hal->batteryMonitor = new AP_BatteryMonitor(batteryPin,batteryVoltageDivRatio,batteryMinVolt,batteryMaxVolt);
}
/**
* Initialize ultrasonic sensors. If sensors are not plugged in, the navigator will not
* initialize them and NULL will be assigned to those corresponding pointers.
* On detecting NULL assigned to any ultrasonic sensor, its corresponding block of code
* will not be executed by the navigator.
* The coordinate system is assigned by the right hand rule with the thumb pointing down.
* In set_orientation, it is defined as (front/back,left/right,down,up)
*/
if (gpsEnabled) {
Serial1.begin(gpsBaud, 128, 16); // gps
hal->debug->println_P(PSTR("initializing gps"));
AP_GPS_Auto gpsDriver(&Serial1, &(hal->gps));
hal->gps = &gpsDriver;
hal->gps->callback = delay;
hal->gps->init();
}
if (rangeFinderFrontEnabled) {
hal->debug->println_P(PSTR("initializing front range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(1);
rangeFinder->set_orientation(1, 0, 0);
hal->rangeFinders.push_back(rangeFinder);
}
if (baroEnabled) {
hal->debug->println_P(PSTR("initializing baro"));
hal->baro = new BARO_CLASS;
hal->baro->Init();
}
if (rangeFinderBackEnabled) {
hal->debug->println_P(PSTR("initializing back range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(2);
rangeFinder->set_orientation(-1, 0, 0);
hal->rangeFinders.push_back(rangeFinder);
}
if (compassEnabled) {
Wire.begin();
hal->debug->println_P(PSTR("initializing compass"));
hal->compass = new COMPASS_CLASS;
hal->compass->set_orientation(compassOrientation);
hal->compass->set_offsets(0,0,0);
hal->compass->set_declination(0.0);
hal->compass->init();
}
if (rangeFinderLeftEnabled) {
hal->debug->println_P(PSTR("initializing left range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(3);
rangeFinder->set_orientation(0, -1, 0);
hal->rangeFinders.push_back(rangeFinder);
}
/**
* Initialize ultrasonic sensors. If sensors are not plugged in, the navigator will not
* initialize them and NULL will be assigned to those corresponding pointers.
* On detecting NULL assigned to any ultrasonic sensor, its corresponding block of code
* will not be executed by the navigator.
* The coordinate system is assigned by the right hand rule with the thumb pointing down.
* In set_orientation, it is defined as (front/back,left/right,down,up)
*/
if (rangeFinderRightEnabled) {
hal->debug->println_P(PSTR("initializing right range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(4);
rangeFinder->set_orientation(0, 1, 0);
hal->rangeFinders.push_back(rangeFinder);
}
if (rangeFinderFrontEnabled) {
hal->debug->println_P(PSTR("initializing front range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(1);
rangeFinder->set_orientation(1, 0, 0);
hal->rangeFinders.push_back(rangeFinder);
}
if (rangeFinderUpEnabled) {
hal->debug->println_P(PSTR("initializing up range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(5);
rangeFinder->set_orientation(0, 0, -1);
hal->rangeFinders.push_back(rangeFinder);
}
if (rangeFinderBackEnabled) {
hal->debug->println_P(PSTR("initializing back range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(2);
rangeFinder->set_orientation(-1, 0, 0);
hal->rangeFinders.push_back(rangeFinder);
}
if (rangeFinderDownEnabled) {
hal->debug->println_P(PSTR("initializing down range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(6);
rangeFinder->set_orientation(0, 0, 1);
hal->rangeFinders.push_back(rangeFinder);
}
if (rangeFinderLeftEnabled) {
hal->debug->println_P(PSTR("initializing left range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(3);
rangeFinder->set_orientation(0, -1, 0);
hal->rangeFinders.push_back(rangeFinder);
}
}
if (rangeFinderRightEnabled) {
hal->debug->println_P(PSTR("initializing right range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(4);
rangeFinder->set_orientation(0, 1, 0);
hal->rangeFinders.push_back(rangeFinder);
}
/*
* Select guidance, navigation, control algorithms
*/
navigator = new NAVIGATOR_CLASS(hal);
guide = new GUIDE_CLASS(navigator, hal);
controller = new CONTROLLER_CLASS(navigator, guide, hal);
if (rangeFinderUpEnabled) {
hal->debug->println_P(PSTR("initializing up range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(5);
rangeFinder->set_orientation(0, 0, -1);
hal->rangeFinders.push_back(rangeFinder);
}
/*
* CommLinks
*/
if (board==BOARD_ARDUPILOTMEGA_2)
{
Serial2.begin(telemBaud, 128, 128); // gcs
hal->gcs = new COMMLINK_CLASS(&Serial2, navigator, guide, controller, hal);
}
else
{
Serial3.begin(telemBaud, 128, 128); // gcs
hal->gcs = new COMMLINK_CLASS(&Serial3, navigator, guide, controller, hal);
}
if (rangeFinderDownEnabled) {
hal->debug->println_P(PSTR("initializing down range finder"));
RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter);
rangeFinder->set_analog_port(6);
rangeFinder->set_orientation(0, 0, 1);
hal->rangeFinders.push_back(rangeFinder);
}
/*
* Hardware in the Loop
*/
if (hal->getMode() == MODE_HIL_CNTL) {
Serial.println("HIL line setting up");
Serial1.begin(hilBaud, 128, 128);
hal->hil = new COMMLINK_CLASS(&Serial1, navigator, guide, controller, hal);
}
}
/*
* Start the autopilot
*/
hal->debug->printf_P(PSTR("initializing autopilot\n"));
hal->debug->printf_P(PSTR("free ram: %d bytes\n"),freeMemory());
/*
* Select guidance, navigation, control algorithms
*/
navigator = new NAVIGATOR_CLASS(hal);
guide = new GUIDE_CLASS(navigator, hal, velCmd, xt, xtLim);
controller = new CONTROLLER_CLASS(navigator,guide,hal);
autoPilot = new apo::AP_Autopilot(navigator, guide, controller, hal,
loopRate, loop0Rate, loop1Rate, loop2Rate, loop3Rate);
/*
* CommLinks
*/
if (board==BOARD_ARDUPILOTMEGA_2)
{
Serial2.begin(telemBaud, 128, 128); // gcs
hal->gcs = new COMMLINK_CLASS(&Serial2, navigator, guide, controller, hal);
}
else
{
Serial3.begin(telemBaud, 128, 128); // gcs
hal->gcs = new COMMLINK_CLASS(&Serial3, navigator, guide, controller, hal);
}
/*
* Hardware in the Loop
*/
if (hal->getMode() == MODE_HIL_CNTL) {
Serial.println("HIL line setting up");
Serial1.begin(hilBaud, 128, 128);
delay(1000);
Serial1.println("starting hil");
hal->hil = new COMMLINK_CLASS(&Serial1, navigator, guide, controller, hal);
}
/*
* Start the autopilot
*/
hal->debug->printf_P(PSTR("initializing autopilot\n"));
hal->debug->printf_P(PSTR("free ram: %d bytes\n"),freeMemory());
autoPilot = new apo::AP_Autopilot(navigator, guide, controller, hal,
loopRate, loop0Rate, loop1Rate, loop2Rate, loop3Rate);
}
void loop() {
autoPilot->update();
autoPilot->update();
}
#endif //_APO_COMMON_H
// vim:ts=4:sw=4:expandtab

View File

@ -0,0 +1,57 @@
/*
* AP_ArmingMechanism.cpp
*
*/
#include "AP_ArmingMechanism.h"
#include "AP_RcChannel.h"
#include "../FastSerial/FastSerial.h"
#include "AP_HardwareAbstractionLayer.h"
#include "AP_CommLink.h"
namespace apo {
void AP_ArmingMechanism::update(const float dt) {
//_hal->debug->printf_P(PSTR("ch1: %f\tch2: %f\n"),_hal->rc[_ch1]->getRadioPosition(), _hal->rc[_ch2]->getRadioPosition());
// arming
if ( (_hal->getState() != MAV_STATE_ACTIVE) &&
(fabs(_hal->rc[_ch1]->getRadioPosition()) < _ch1Min) &&
(_hal->rc[_ch2]->getRadioPosition() < _ch2Min) ) {
// always start clock at 0
if (_armingClock<0) _armingClock = 0;
if (_armingClock++ >= 100) {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed"));
_hal->setState(MAV_STATE_ACTIVE);
} else {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("arming"));
}
}
// disarming
else if ( (_hal->getState() == MAV_STATE_ACTIVE) &&
(fabs(_hal->rc[_ch1]->getRadioPosition()) < _ch1Min) &&
(_hal->rc[_ch2]->getRadioPosition() > _ch2Max) ) {
// always start clock at 0
if (_armingClock>0) _armingClock = 0;
if (_armingClock-- <= -100) {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed"));
_hal->setState(MAV_STATE_STANDBY);
} else {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarming"));
}
}
// reset arming clock and report status
else if (_armingClock != 0) {
_armingClock = 0;
if (_hal->getState()==MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed"));
else if (_hal->getState()!=MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed"));
}
}
} // apo
// vim:ts=4:sw=4:expandtab

View File

@ -0,0 +1,67 @@
/*
* AP_ArmingMechanism.h
*
*/
#ifndef AP_ARMINGMECHANISM_H_
#define AP_ARMINGMECHANISM_H_
#include <inttypes.h>
#include <wiring.h>
namespace apo {
class AP_HardwareAbstractionLayer;
class AP_ArmingMechanism {
public:
/**
* Constructor
*
* @param ch1: typically throttle channel
* @param ch2: typically yaw channel
* @param ch1Min: disarms/arms belows this
* @param ch2Min: disarms below this
* @param ch2Max: arms above this
*/
AP_ArmingMechanism(AP_HardwareAbstractionLayer * hal,
uint8_t ch1, uint8_t ch2, float ch1Min, float ch2Min,
float ch2Max) : _armingClock(0), _hal(hal), _ch1(ch1), _ch2(ch2),
_ch1Min(ch1Min), _ch2Min(ch2Min), _ch2Max(ch2Max) {
}
/**
* update
*
* arming:
*
* to arm: put stick to bottom right for 100 controller cycles
* (max yaw, min throttle)
*
* didn't use clock here in case of millis() roll over
* for long runs
*
* disarming:
*
* to disarm: put stick to bottom left for 100 controller cycles
* (min yaw, min throttle)
*/
void update(const float dt);
private:
AP_HardwareAbstractionLayer * _hal;
int8_t _armingClock;
uint8_t _ch1; /// typically throttle channel
uint8_t _ch2; /// typically yaw channel
float _ch1Min; /// arms/disarms below this on ch1
float _ch2Min; /// disarms below this on ch2
float _ch2Max; /// arms above this on ch2
};
} // namespace apo
#endif /* AP_ARMINGMECHANISM */
// vim:ts=4:sw=4:expandtab

View File

@ -5,250 +5,269 @@
* Author: jgoppert
*/
/*
* AVR runtime
*/
//#include <avr/io.h>
//#include <avr/eeprom.h>
//#include <avr/pgmspace.h>
//#include <math.h>
#include "../FastSerial/FastSerial.h"
#include "AP_Autopilot.h"
#include "../AP_GPS/AP_GPS.h"
#include "../APM_RC/APM_RC.h"
#include "AP_HardwareAbstractionLayer.h"
#include "AP_CommLink.h"
#include "AP_MavlinkCommand.h"
#include "AP_Navigator.h"
#include "AP_Controller.h"
#include "AP_Guide.h"
#include "AP_BatteryMonitor.h"
namespace apo {
class AP_HardwareAbstractionLayer;
AP_Autopilot::AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide,
AP_Controller * controller, AP_HardwareAbstractionLayer * hal,
float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate) :
Loop(loopRate, callback, this), _navigator(navigator), _guide(guide),
_controller(controller), _hal(hal),
callbackCalls(0) {
AP_Controller * controller, AP_HardwareAbstractionLayer * hal,
float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate) :
Loop(loopRate, callback, this), _navigator(navigator), _guide(guide),
_controller(controller), _hal(hal),
callbackCalls(0) {
hal->setState(MAV_STATE_BOOT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
hal->setState(MAV_STATE_BOOT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
/*
* Radio setup
*/
hal->debug->println_P(PSTR("initializing radio"));
APM_RC.Init(); // APM Radio initialization,
/*
* Radio setup
*/
hal->debug->println_P(PSTR("initializing radio"));
APM_RC.Init(); // APM Radio initialization,
/*
* Calibration
*/
hal->setState(MAV_STATE_CALIBRATING);
hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
/*
* Calibration
*/
hal->setState(MAV_STATE_CALIBRATING);
hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
if (navigator) navigator->calibrate();
if (navigator) navigator->calibrate();
/*
* Look for valid initial state
*/
while (_navigator) {
// letc gcs known we are alive
hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
if (hal->getMode() == MODE_LIVE) {
_navigator->updateSlow(0);
if (hal->gps) {
if (hal->gps->fix) {
break;
} else {
hal->gps->update();
hal->gcs->sendText(SEVERITY_LOW,
PSTR("waiting for gps lock\n"));
hal->debug->printf_P(PSTR("waiting for gps lock\n"));
}
} else { // no gps, can skip
break;
}
} else if (hal->getMode() == MODE_HIL_CNTL) { // hil
hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->hil->receive();
Serial.println("HIL Receive Called");
if (_navigator->getTimeStamp() != 0) {
// give hil a chance to send some packets
for (int i = 0; i < 5; i++) {
hal->debug->println_P(PSTR("reading initial hil packets"));
hal->gcs->sendText(SEVERITY_LOW,
PSTR("reading initial hil packets"));
delay(1000);
}
break;
}
hal->debug->println_P(PSTR("waiting for hil packet"));
}
delay(500);
}
AP_MavlinkCommand::home.setAlt(_navigator->getAlt());
AP_MavlinkCommand::home.setLat(_navigator->getLat());
AP_MavlinkCommand::home.setLon(_navigator->getLon());
AP_MavlinkCommand::home.setCommand(MAV_CMD_NAV_WAYPOINT);
AP_MavlinkCommand::home.save();
_hal->debug->printf_P(PSTR("\nhome before load lat: %f deg, lon: %f deg, cmd: %d\n"),
AP_MavlinkCommand::home.getLat()*rad2Deg,
AP_MavlinkCommand::home.getLon()*rad2Deg,
AP_MavlinkCommand::home.getCommand());
AP_MavlinkCommand::home.load();
_hal->debug->printf_P(PSTR("\nhome after load lat: %f deg, lon: %f deg, cmd: %d\n"),
AP_MavlinkCommand::home.getLat()*rad2Deg,
AP_MavlinkCommand::home.getLon()*rad2Deg,
AP_MavlinkCommand::home.getCommand());
/*
* Look for valid initial state
*/
while (_navigator) {
// letc gcs known we are alive
hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
if (hal->getMode() == MODE_LIVE) {
_navigator->updateSlow(0);
if (hal->gps) {
if (hal->gps->fix) {
break;
} else {
hal->gps->update();
hal->gcs->sendText(SEVERITY_LOW,
PSTR("waiting for gps lock\n"));
hal->debug->printf_P(PSTR("waiting for gps lock\n"));
}
} else { // no gps, can skip
break;
}
} else if (hal->getMode() == MODE_HIL_CNTL) { // hil
hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
hal->hil->receive();
Serial.println("HIL Receive Called");
if (_navigator->getTimeStamp() != 0) {
// give hil a chance to send some packets
for (int i = 0; i < 5; i++) {
hal->debug->println_P(PSTR("reading initial hil packets"));
hal->gcs->sendText(SEVERITY_LOW,
PSTR("reading initial hil packets"));
delay(1000);
}
break;
}
hal->debug->println_P(PSTR("waiting for hil packet"));
}
delay(500);
}
/*
* Attach loops
*/
hal->debug->println_P(PSTR("attaching loops"));
subLoops().push_back(new Loop(loop0Rate, callback0, this));
subLoops().push_back(new Loop(loop1Rate, callback1, this));
subLoops().push_back(new Loop(loop2Rate, callback2, this));
subLoops().push_back(new Loop(loop3Rate, callback3, this));
AP_MavlinkCommand::home.setAlt(_navigator->getAlt());
AP_MavlinkCommand::home.setLat(_navigator->getLat());
AP_MavlinkCommand::home.setLon(_navigator->getLon());
AP_MavlinkCommand::home.setCommand(MAV_CMD_NAV_WAYPOINT);
AP_MavlinkCommand::home.save();
_hal->debug->printf_P(PSTR("\nhome before load lat: %f deg, lon: %f deg, cmd: %d\n"),
AP_MavlinkCommand::home.getLat()*rad2Deg,
AP_MavlinkCommand::home.getLon()*rad2Deg,
AP_MavlinkCommand::home.getCommand());
AP_MavlinkCommand::home.load();
_hal->debug->printf_P(PSTR("\nhome after load lat: %f deg, lon: %f deg, cmd: %d\n"),
AP_MavlinkCommand::home.getLat()*rad2Deg,
AP_MavlinkCommand::home.getLon()*rad2Deg,
AP_MavlinkCommand::home.getCommand());
hal->debug->println_P(PSTR("running"));
hal->gcs->sendText(SEVERITY_LOW, PSTR("running"));
hal->setState(MAV_STATE_STANDBY);
/*
* Attach loops, stacking for priority
*/
hal->debug->println_P(PSTR("attaching loops"));
subLoops().push_back(new Loop(loop0Rate, callback0, this));
subLoops().push_back(new Loop(loop1Rate, callback1, this));
subLoops().push_back(new Loop(loop2Rate, callback2, this));
subLoops().push_back(new Loop(loop3Rate, callback3, this));
hal->debug->println_P(PSTR("running"));
hal->gcs->sendText(SEVERITY_LOW, PSTR("running"));
hal->setState(MAV_STATE_STANDBY);
}
void AP_Autopilot::callback(void * data) {
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->hal()->debug->println_P(PSTR("callback"));
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->hal()->debug->println_P(PSTR("callback"));
/*
* ahrs update
*/
apo->callbackCalls++;
if (apo->getNavigator())
apo->getNavigator()->updateFast(apo->dt());
/*
* ahrs update
*/
apo->callbackCalls++;
if (apo->getNavigator())
apo->getNavigator()->updateFast(apo->dt());
}
void AP_Autopilot::callback0(void * data) {
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 0"));
/*
* hardware in the loop
*/
if (apo->getHal()->hil && apo->getHal()->getMode() != MODE_LIVE) {
apo->getHal()->hil->receive();
apo->getHal()->hil->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED);
}
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 0"));
/*
* update control laws
*/
if (apo->getController()) {
//apo->getHal()->debug->println_P(PSTR("updating controller"));
apo->getController()->update(apo->subLoops()[0]->dt());
}
/*
char msg[50];
sprintf(msg, "c_hdg: %f, c_thr: %f", apo->guide()->headingCommand, apo->guide()->groundSpeedCommand);
apo->hal()->gcs->sendText(AP_CommLink::SEVERITY_LOW, msg);
*/
* hardware in the loop
*/
if (apo->getHal()->hil && apo->getHal()->getMode() != MODE_LIVE) {
apo->getHal()->hil->receive();
apo->getHal()->hil->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED);
}
/*
* update control laws
*/
if (apo->getController()) {
//apo->getHal()->debug->println_P(PSTR("updating controller"));
apo->getController()->update(apo->subLoops()[0]->dt());
}
/*
char msg[50];
sprintf(msg, "c_hdg: %f, c_thr: %f", apo->guide()->headingCommand, apo->guide()->groundSpeedCommand);
apo->hal()->gcs->sendText(AP_CommLink::SEVERITY_LOW, msg);
*/
}
void AP_Autopilot::callback1(void * data) {
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 1"));
/*
* update guidance laws
*/
if (apo->getGuide())
{
//apo->getHal()->debug->println_P(PSTR("updating guide"));
apo->getGuide()->update();
}
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 1"));
/*
* slow navigation loop update
*/
if (apo->getNavigator()) {
apo->getNavigator()->updateSlow(apo->subLoops()[1]->dt());
}
/*
* update guidance laws
*/
if (apo->getGuide())
{
//apo->getHal()->debug->println_P(PSTR("updating guide"));
apo->getGuide()->update();
}
/*
* send telemetry
*/
if (apo->getHal()->gcs) {
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_ATTITUDE);
}
/*
* slow navigation loop update
*/
if (apo->getNavigator()) {
apo->getNavigator()->updateSlow(apo->subLoops()[1]->dt());
}
/*
* handle ground control station communication
*/
if (apo->getHal()->gcs) {
// send messages
apo->getHal()->gcs->requestCmds();
apo->getHal()->gcs->sendParameters();
/*
* send telemetry
*/
if (apo->getHal()->gcs) {
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_ATTITUDE);
}
// receive messages
apo->getHal()->gcs->receive();
}
/*
* handle ground control station communication
*/
if (apo->getHal()->gcs) {
// send messages
apo->getHal()->gcs->requestCmds();
apo->getHal()->gcs->sendParameters();
/*
* navigator debug
*/
/*
if (apo->navigator()) {
apo->getHal()->debug->printf_P(PSTR("roll: %f deg\tpitch: %f deg\tyaw: %f deg\n"),
apo->navigator()->getRoll()*rad2Deg,
apo->navigator()->getPitch()*rad2Deg,
apo->navigator()->getYaw()*rad2Deg);
apo->getHal()->debug->printf_P(PSTR("lat: %f deg\tlon: %f deg\talt: %f m\n"),
apo->navigator()->getLat()*rad2Deg,
apo->navigator()->getLon()*rad2Deg,
apo->navigator()->getAlt());
}
*/
// receive messages
apo->getHal()->gcs->receive();
}
/*
* navigator debug
*/
/*
if (apo->navigator()) {
apo->getHal()->debug->printf_P(PSTR("roll: %f deg\tpitch: %f deg\tyaw: %f deg\n"),
apo->navigator()->getRoll()*rad2Deg,
apo->navigator()->getPitch()*rad2Deg,
apo->navigator()->getYaw()*rad2Deg);
apo->getHal()->debug->printf_P(PSTR("lat: %f deg\tlon: %f deg\talt: %f m\n"),
apo->navigator()->getLat()*rad2Deg,
apo->navigator()->getLon()*rad2Deg,
apo->navigator()->getAlt());
}
*/
}
void AP_Autopilot::callback2(void * data) {
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 2"));
/*
* send telemetry
*/
if (apo->getHal()->gcs) {
// send messages
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GPS_RAW);
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED);
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GLOBAL_POSITION);
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_RAW);
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SCALED_IMU);
}
AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 2"));
/*
* update battery monitor
*/
if (apo->getHal()->batteryMonitor) apo->getHal()->batteryMonitor->update();
/*
* send telemetry
*/
if (apo->getHal()->gcs) {
// send messages
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GPS_RAW);
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED);
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_RAW);
//apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GLOBAL_POSITION);
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SCALED_IMU);
}
/*
* send heartbeat
*/
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
/*
* update battery monitor
*/
if (apo->getHal()->batteryMonitor) apo->getHal()->batteryMonitor->update();
/*
* load/loop rate/ram debug
*/
apo->getHal()->load = apo->load();
apo->getHal()->debug->printf_P(PSTR("callback calls: %d\n"),apo->callbackCalls);
apo->callbackCalls = 0;
apo->getHal()->debug->printf_P(PSTR("load: %d%%\trate: %f Hz\tfree ram: %d bytes\n"),
apo->load(),1.0/apo->dt(),freeMemory());
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
/*
* send heartbeat
*/
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT);
/*
* adc debug
*/
//apo->getDebug().printf_P(PSTR("adc: %d %d %d %d %d %d %d %d\n"),
//apo->adc()->Ch(0), apo->adc()->Ch(1), apo->adc()->Ch(2),
//apo->adc()->Ch(3), apo->adc()->Ch(4), apo->adc()->Ch(5),
//apo->adc()->Ch(6), apo->adc()->Ch(7), apo->adc()->Ch(8));
/*
* load/loop rate/ram debug
*/
apo->getHal()->load = apo->load();
apo->getHal()->debug->printf_P(PSTR("callback calls: %d\n"),apo->callbackCalls);
apo->callbackCalls = 0;
apo->getHal()->debug->printf_P(PSTR("load: %d%%\trate: %f Hz\tfree ram: %d bytes\n"),
apo->load(),1.0/apo->dt(),freeMemory());
apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS);
/*
* adc debug
*/
//apo->getDebug().printf_P(PSTR("adc: %d %d %d %d %d %d %d %d\n"),
//apo->adc()->Ch(0), apo->adc()->Ch(1), apo->adc()->Ch(2),
//apo->adc()->Ch(3), apo->adc()->Ch(4), apo->adc()->Ch(5),
//apo->adc()->Ch(6), apo->adc()->Ch(7), apo->adc()->Ch(8));
}
void AP_Autopilot::callback3(void * data) {
//AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 3"));
//AP_Autopilot * apo = (AP_Autopilot *) data;
//apo->getHal()->debug->println_P(PSTR("callback 3"));
}
} // apo
// vim:ts=4:sw=4:expandtab

View File

@ -8,38 +8,7 @@
#ifndef AP_AUTOPILOT_H_
#define AP_AUTOPILOT_H_
/*
* AVR runtime
*/
#include <avr/io.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <math.h>
/*
* Libraries
*/
#include "../AP_Common/AP_Common.h"
#include "../FastSerial/FastSerial.h"
#include "../AP_GPS/GPS.h"
#include "../APM_RC/APM_RC.h"
#include "../AP_ADC/AP_ADC.h"
#include "../APM_BMP085/APM_BMP085.h"
#include "../AP_Compass/AP_Compass.h"
#include "../AP_Math/AP_Math.h"
#include "../AP_IMU/AP_IMU.h"
#include "../AP_DCM/AP_DCM.h"
#include "../AP_Common/AP_Loop.h"
#include "../GCS_MAVLink/GCS_MAVLink.h"
#include "../AP_RangeFinder/AP_RangeFinder.h"
/*
* Local Modules
*/
#include "AP_HardwareAbstractionLayer.h"
#include "AP_RcChannel.h"
#include "AP_Controller.h"
#include "AP_Navigator.h"
#include "AP_Guide.h"
#include "AP_CommLink.h"
/**
* ArduPilotOne namespace to protect variables
@ -50,7 +19,10 @@
namespace apo {
// forward declarations
class AP_CommLink;
class AP_Navigator;
class AP_Guide;
class AP_Controller;
class AP_HardwareAbstractionLayer;
/**
* This class encapsulates the entire autopilot system
@ -65,90 +37,91 @@ class AP_CommLink;
*/
class AP_Autopilot: public Loop {
public:
/**
* Default constructor
*/
AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide,
AP_Controller * controller, AP_HardwareAbstractionLayer * hal,
float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate);
/**
* Default constructor
*/
AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide,
AP_Controller * controller, AP_HardwareAbstractionLayer * hal,
float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate);
/**
* Accessors
*/
AP_Navigator * getNavigator() {
return _navigator;
}
AP_Guide * getGuide() {
return _guide;
}
AP_Controller * getController() {
return _controller;
}
AP_HardwareAbstractionLayer * getHal() {
return _hal;
}
/**
* Accessors
*/
AP_Navigator * getNavigator() {
return _navigator;
}
AP_Guide * getGuide() {
return _guide;
}
AP_Controller * getController() {
return _controller;
}
AP_HardwareAbstractionLayer * getHal() {
return _hal;
}
/**
* Loop Monitoring
*/
uint32_t callbackCalls;
/**
* Loop Monitoring
*/
uint32_t callbackCalls;
private:
/**
* Loop Callbacks (fastest)
* - inertial navigation
* @param data A void pointer used to pass the apo class
* so that the apo public interface may be accessed.
*/
static void callback(void * data);
/**
* Loop Callbacks (fastest)
* - inertial navigation
* @param data A void pointer used to pass the apo class
* so that the apo public interface may be accessed.
*/
static void callback(void * data);
/**
* Loop 0 Callbacks
* - control
* - compass reading
* @see callback
*/
static void callback0(void * data);
/**
* Loop 0 Callbacks
* - control
* - compass reading
* @see callback
*/
static void callback0(void * data);
/**
* Loop 1 Callbacks
* - gps sensor fusion
* - compass sensor fusion
* @see callback
*/
static void callback1(void * data);
/**
* Loop 1 Callbacks
* - gps sensor fusion
* - compass sensor fusion
* @see callback
*/
static void callback1(void * data);
/**
* Loop 2 Callbacks
* - slow messages
* @see callback
*/
static void callback2(void * data);
/**
* Loop 2 Callbacks
* - slow messages
* @see callback
*/
static void callback2(void * data);
/**
* Loop 3 Callbacks
* - super slow messages
* - log writing
* @see callback
*/
static void callback3(void * data);
/**
* Loop 3 Callbacks
* - super slow messages
* - log writing
* @see callback
*/
static void callback3(void * data);
/**
* Components
*/
AP_Navigator * _navigator;
AP_Guide * _guide;
AP_Controller * _controller;
AP_HardwareAbstractionLayer * _hal;
/**
* Components
*/
AP_Navigator * _navigator;
AP_Guide * _guide;
AP_Controller * _controller;
AP_HardwareAbstractionLayer * _hal;
/**
* Constants
*/
static const float deg2rad = M_PI / 180;
static const float rad2deg = 180 / M_PI;
/**
* Constants
*/
static const float deg2rad = M_PI / 180;
static const float rad2deg = 180 / M_PI;
};
} // namespace apo
#endif /* AP_AUTOPILOT_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -8,3 +8,5 @@
namespace apo {
} // apo
// vim:ts=4:sw=4:expandtab

View File

@ -13,39 +13,40 @@ namespace apo {
class AP_BatteryMonitor {
public:
AP_BatteryMonitor(uint8_t pin, float voltageDivRatio, float minVolt, float maxVolt) :
_pin(pin), _voltageDivRatio(voltageDivRatio),
_minVolt(minVolt), _maxVolt(maxVolt), _voltage(maxVolt) {
}
AP_BatteryMonitor(uint8_t pin, float voltageDivRatio, float minVolt, float maxVolt) :
_pin(pin), _voltageDivRatio(voltageDivRatio),
_minVolt(minVolt), _maxVolt(maxVolt), _voltage(maxVolt) {
}
void update() {
// low pass filter on voltage
_voltage = _voltage*.9 + (analogRead(_pin)/255)*_voltageDivRatio*0.1;
}
void update() {
// low pass filter on voltage
_voltage = _voltage*.9 + (analogRead(_pin)/255)*_voltageDivRatio*0.1;
}
/**
* Accessors
*/
float getVoltage() {
return _voltage;
}
/**
* Accessors
*/
float getVoltage() {
return _voltage;
}
uint8_t getPercentage() {
float norm = (_voltage-_minVolt)/(_maxVolt-_minVolt);
if (norm < 0) norm = 0;
else if (norm > 1) norm = 1;
return 100*norm;
}
uint8_t getPercentage() {
float norm = (_voltage-_minVolt)/(_maxVolt-_minVolt);
if (norm < 0) norm = 0;
else if (norm > 1) norm = 1;
return 100*norm;
}
private:
uint8_t _pin;
float _voltageDivRatio;
float _voltage;
float _minVolt;
float _maxVolt;
uint8_t _pin;
float _voltageDivRatio;
float _voltage;
float _minVolt;
float _maxVolt;
};
} // namespace apo
#endif /* AP_BATTERYMONITOR_H_ */
// vim:ts=4:sw=4:expandtab

File diff suppressed because it is too large Load Diff

View File

@ -22,7 +22,7 @@
#include <inttypes.h>
#include "../AP_Common/AP_Common.h"
#include "../AP_Common/AP_Vector.h"
#include "AP_MavlinkCommand.h"
#include "../GCS_MAVLink/GCS_MAVLink.h"
class FastSerial;
@ -34,7 +34,7 @@ class AP_Guide;
class AP_HardwareAbstractionLayer;
enum {
SEVERITY_LOW, SEVERITY_MED, SEVERITY_HIGH
SEVERITY_LOW, SEVERITY_MED, SEVERITY_HIGH
};
// forward declarations
@ -45,83 +45,83 @@ enum {
class AP_CommLink {
public:
AP_CommLink(FastSerial * link, AP_Navigator * navigator, AP_Guide * guide,
AP_Controller * controller, AP_HardwareAbstractionLayer * hal);
virtual void send() = 0;
virtual void receive() = 0;
virtual void sendMessage(uint8_t id, uint32_t param = 0) = 0;
virtual void sendText(uint8_t severity, const char *str) = 0;
virtual void sendText(uint8_t severity, const prog_char_t *str) = 0;
virtual void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) = 0;
virtual void sendParameters() = 0;
virtual void requestCmds() = 0;
AP_CommLink(FastSerial * link, AP_Navigator * navigator, AP_Guide * guide,
AP_Controller * controller, AP_HardwareAbstractionLayer * hal);
virtual void send() = 0;
virtual void receive() = 0;
virtual void sendMessage(uint8_t id, uint32_t param = 0) = 0;
virtual void sendText(uint8_t severity, const char *str) = 0;
virtual void sendText(uint8_t severity, const prog_char_t *str) = 0;
virtual void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) = 0;
virtual void sendParameters() = 0;
virtual void requestCmds() = 0;
protected:
FastSerial * _link;
AP_Navigator * _navigator;
AP_Guide * _guide;
AP_Controller * _controller;
AP_HardwareAbstractionLayer * _hal;
FastSerial * _link;
AP_Navigator * _navigator;
AP_Guide * _guide;
AP_Controller * _controller;
AP_HardwareAbstractionLayer * _hal;
};
class MavlinkComm: public AP_CommLink {
public:
MavlinkComm(FastSerial * link, AP_Navigator * nav, AP_Guide * guide,
AP_Controller * controller, AP_HardwareAbstractionLayer * hal);
MavlinkComm(FastSerial * link, AP_Navigator * nav, AP_Guide * guide,
AP_Controller * controller, AP_HardwareAbstractionLayer * hal);
virtual void send();
void sendMessage(uint8_t id, uint32_t param = 0);
virtual void receive();
void sendText(uint8_t severity, const char *str);
void sendText(uint8_t severity, const prog_char_t *str);
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
virtual void send();
void sendMessage(uint8_t id, uint32_t param = 0);
virtual void receive();
void sendText(uint8_t severity, const char *str);
void sendText(uint8_t severity, const prog_char_t *str);
void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2);
/**
* sends parameters one at a time
*/
void sendParameters();
/**
* sends parameters one at a time
*/
void sendParameters();
/**
* request commands one at a time
*/
void requestCmds();
/**
* request commands one at a time
*/
void requestCmds();
private:
// options
bool _useRelativeAlt;
// options
bool _useRelativeAlt;
// commands
bool _sendingCmds;
bool _receivingCmds;
uint16_t _cmdTimeLastSent;
uint16_t _cmdTimeLastReceived;
uint16_t _cmdDestSysId;
uint16_t _cmdDestCompId;
uint16_t _cmdRequestIndex;
uint16_t _cmdNumberRequested;
uint16_t _cmdMax;
Vector<mavlink_command_t *> _cmdList;
// commands
bool _sendingCmds;
bool _receivingCmds;
uint16_t _cmdTimeLastSent;
uint16_t _cmdTimeLastReceived;
uint16_t _cmdDestSysId;
uint16_t _cmdDestCompId;
uint16_t _cmdRequestIndex;
uint16_t _cmdNumberRequested;
uint16_t _cmdMax;
Vector<mavlink_command_t *> _cmdList;
// parameters
static uint8_t _paramNameLengthMax;
uint16_t _parameterCount;
AP_Var * _queuedParameter;
uint16_t _queuedParameterIndex;
// parameters
static uint8_t _paramNameLengthMax;
uint16_t _parameterCount;
AP_Var * _queuedParameter;
uint16_t _queuedParameterIndex;
// channel
mavlink_channel_t _channel;
uint16_t _packetDrops;
static uint8_t _nChannels;
// channel
mavlink_channel_t _channel;
uint16_t _packetDrops;
static uint8_t _nChannels;
void _handleMessage(mavlink_message_t * msg);
void _handleMessage(mavlink_message_t * msg);
uint16_t _countParameters();
uint16_t _countParameters();
AP_Var * _findParameter(uint16_t index);
AP_Var * _findParameter(uint16_t index);
// check the target
uint8_t _checkTarget(uint8_t sysid, uint8_t compid);
// check the target
uint8_t _checkTarget(uint8_t sysid, uint8_t compid);
};

View File

@ -6,28 +6,118 @@
*/
#include "AP_Controller.h"
#include "../FastSerial/FastSerial.h"
#include "AP_ArmingMechanism.h"
#include "AP_BatteryMonitor.h"
#include "AP_HardwareAbstractionLayer.h"
#include "../AP_Common/include/menu.h"
#include "AP_RcChannel.h"
#include "../GCS_MAVLink/include/mavlink_types.h"
#include "constants.h"
#include "AP_CommLink.h"
namespace apo {
AP_Controller::AP_Controller(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal) :
_nav(nav), _guide(guide), _hal(hal) {
setAllRadioChannelsToNeutral();
AP_HardwareAbstractionLayer * hal, AP_ArmingMechanism * armingMechanism,
const uint8_t chMode, const uint16_t key, const prog_char_t * name) :
_nav(nav), _guide(guide), _hal(hal), _armingMechanism(armingMechanism),
_group(key, name ? : PSTR("CNTRL_")),
_chMode(chMode),
_mode(&_group, 1, MAV_MODE_LOCKED, PSTR("MODE")) {
setAllRadioChannelsToNeutral();
}
void AP_Controller::setAllRadioChannelsToNeutral() {
for (uint8_t i = 0; i < _hal->rc.getSize(); i++) {
_hal->rc[i]->setPosition(0.0);
}
for (uint8_t i = 0; i < _hal->rc.getSize(); i++) {
_hal->rc[i]->setPosition(0.0);
}
}
void AP_Controller::setAllRadioChannelsManually() {
for (uint8_t i = 0; i < _hal->rc.getSize(); i++) {
_hal->rc[i]->setUsingRadio();
}
for (uint8_t i = 0; i < _hal->rc.getSize(); i++) {
_hal->rc[i]->setUsingRadio();
}
}
void AP_Controller::update(const float dt) {
if (_armingMechanism) _armingMechanism->update(dt);
// determine flight mode
//
// check for heartbeat from gcs, if not found go to failsafe
if (_hal->heartBeatLost()) {
_mode = MAV_MODE_FAILSAFE;
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("configure gcs to send heartbeat"));
// if battery less than 5%, go to failsafe
} else if (_hal->batteryMonitor && _hal->batteryMonitor->getPercentage() < 5) {
_mode = MAV_MODE_FAILSAFE;
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("recharge battery"));
// manual/auto switch
} else {
// if all emergencies cleared, fall back to standby
if (_hal->getState()==MAV_STATE_EMERGENCY) _hal->setState(MAV_STATE_STANDBY);
if (_hal->rc[_chMode]->getRadioPosition() > 0) _mode = MAV_MODE_MANUAL;
else _mode = MAV_MODE_AUTO;
}
// handle flight modes
switch(_mode) {
case MAV_MODE_LOCKED: {
_hal->setState(MAV_STATE_STANDBY);
break;
}
case MAV_MODE_FAILSAFE: {
_hal->setState(MAV_STATE_EMERGENCY);
break;
}
case MAV_MODE_MANUAL: {
manualLoop(dt);
break;
}
case MAV_MODE_AUTO: {
autoLoop(dt);
break;
}
default: {
_hal->gcs->sendText(SEVERITY_HIGH, PSTR("unknown mode"));
_hal->setState(MAV_STATE_EMERGENCY);
}
}
// this sends commands to motors
setMotors();
}
void AP_Controller::setMotors() {
switch (_hal->getState()) {
case MAV_STATE_ACTIVE: {
digitalWrite(_hal->aLedPin, HIGH);
setMotorsActive();
}
case MAV_STATE_EMERGENCY: {
digitalWrite(_hal->aLedPin, LOW);
setMotorsEmergency();
break;
}
case MAV_STATE_STANDBY: {
digitalWrite(_hal->aLedPin,LOW);
setMotorsStandby();
break;
}
default: {
setMotorsStandby();
}
}
}
} // namespace apo
// vim:ts=4:sw=4:expandtab

View File

@ -22,6 +22,8 @@
#include <inttypes.h>
#include "../GCS_MAVLink/GCS_MAVLink.h"
#include <math.h>
#include "../AP_Common/AP_Var.h"
#include "AP_Var_keys.h"
class AP_Var_group;
@ -31,269 +33,293 @@ class AP_HardwareAbstractionLayer;
class AP_Guide;
class AP_Navigator;
class Menu;
class AP_ArmingMechanism;
/// Controller class
class AP_Controller {
public:
AP_Controller(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal);
virtual void update(const float & dt) = 0;
virtual MAV_MODE getMode() = 0;
void setAllRadioChannelsToNeutral();
void setAllRadioChannelsManually();
AP_Controller(AP_Navigator * nav, AP_Guide * guide,
AP_HardwareAbstractionLayer * hal,
AP_ArmingMechanism * armingMechanism,
const uint8_t _chMode,
const uint16_t key = k_cntrl,
const prog_char_t * name = NULL);
virtual void update(const float dt);
void setAllRadioChannelsToNeutral();
void setAllRadioChannelsManually();
virtual void setMotors();
virtual void setMotorsActive() = 0;
virtual void setMotorsEmergency() {
setAllRadioChannelsToNeutral();
};
virtual void setMotorsStandby() {
setAllRadioChannelsToNeutral();
};
virtual void manualLoop(const float dt) {
setAllRadioChannelsToNeutral();
};
virtual void autoLoop(const float dt) {
setAllRadioChannelsToNeutral();
};
AP_Uint8 getMode() {
return _mode;
}
protected:
AP_Navigator * _nav;
AP_Guide * _guide;
AP_HardwareAbstractionLayer * _hal;
AP_Navigator * _nav;
AP_Guide * _guide;
AP_HardwareAbstractionLayer * _hal;
AP_ArmingMechanism * _armingMechanism;
uint8_t _chMode;
AP_Var_group _group;
AP_Uint8 _mode;
};
class AP_ControllerBlock {
public:
AP_ControllerBlock(AP_Var_group * group, uint8_t groupStart,
uint8_t groupLength) :
_group(group), _groupStart(groupStart),
_groupEnd(groupStart + groupLength) {
}
uint8_t getGroupEnd() {
return _groupEnd;
}
AP_ControllerBlock(AP_Var_group * group, uint8_t groupStart,
uint8_t groupLength) :
_group(group), _groupStart(groupStart),
_groupEnd(groupStart + groupLength) {
}
uint8_t getGroupEnd() {
return _groupEnd;
}
protected:
AP_Var_group * _group; /// helps with parameter management
uint8_t _groupStart;
uint8_t _groupEnd;
AP_Var_group * _group; /// helps with parameter management
uint8_t _groupStart;
uint8_t _groupEnd;
};
class BlockLowPass: public AP_ControllerBlock {
public:
BlockLowPass(AP_Var_group * group, uint8_t groupStart, float fCut,
const prog_char_t * fCutLabel = NULL) :
AP_ControllerBlock(group, groupStart, 1),
_fCut(group, groupStart, fCut, fCutLabel ? : PSTR("fCut")),
_y(0) {
}
float update(const float & input, const float & dt) {
float RC = 1 / (2 * M_PI * _fCut); // low pass filter
_y = _y + (input - _y) * (dt / (dt + RC));
return _y;
}
BlockLowPass(AP_Var_group * group, uint8_t groupStart, float fCut,
const prog_char_t * fCutLabel = NULL) :
AP_ControllerBlock(group, groupStart, 1),
_fCut(group, groupStart, fCut, fCutLabel ? : PSTR("fCut")),
_y(0) {
}
float update(const float & input, const float & dt) {
float RC = 1 / (2 * M_PI * _fCut); // low pass filter
_y = _y + (input - _y) * (dt / (dt + RC));
return _y;
}
protected:
AP_Float _fCut;
float _y;
AP_Float _fCut;
float _y;
};
class BlockSaturation: public AP_ControllerBlock {
public:
BlockSaturation(AP_Var_group * group, uint8_t groupStart, float yMax,
const prog_char_t * yMaxLabel = NULL) :
AP_ControllerBlock(group, groupStart, 1),
_yMax(group, groupStart, yMax, yMaxLabel ? : PSTR("yMax")) {
}
float update(const float & input) {
BlockSaturation(AP_Var_group * group, uint8_t groupStart, float yMax,
const prog_char_t * yMaxLabel = NULL) :
AP_ControllerBlock(group, groupStart, 1),
_yMax(group, groupStart, yMax, yMaxLabel ? : PSTR("yMax")) {
}
float update(const float & input) {
// pid sum
float y = input;
// pid sum
float y = input;
// saturation
if (y > _yMax)
y = _yMax;
if (y < -_yMax)
y = -_yMax;
return y;
}
// saturation
if (y > _yMax)
y = _yMax;
if (y < -_yMax)
y = -_yMax;
return y;
}
protected:
AP_Float _yMax; /// output saturation
AP_Float _yMax; /// output saturation
};
class BlockDerivative {
public:
BlockDerivative() :
_lastInput(0), firstRun(true) {
}
float update(const float & input, const float & dt) {
float derivative = (input - _lastInput) / dt;
_lastInput = input;
if (firstRun) {
firstRun = false;
return 0;
} else
return derivative;
}
BlockDerivative() :
_lastInput(0), firstRun(true) {
}
float update(const float & input, const float & dt) {
float derivative = (input - _lastInput) / dt;
_lastInput = input;
if (firstRun) {
firstRun = false;
return 0;
} else
return derivative;
}
protected:
float _lastInput; /// last input
bool firstRun;
float _lastInput; /// last input
bool firstRun;
};
class BlockIntegral {
public:
BlockIntegral() :
_i(0) {
}
float update(const float & input, const float & dt) {
_i += input * dt;
return _i;
}
BlockIntegral() :
_i(0) {
}
float update(const float & input, const float & dt) {
_i += input * dt;
return _i;
}
protected:
float _i; /// integral
float _i; /// integral
};
class BlockP: public AP_ControllerBlock {
public:
BlockP(AP_Var_group * group, uint8_t groupStart, float kP,
const prog_char_t * kPLabel = NULL) :
AP_ControllerBlock(group, groupStart, 1),
_kP(group, groupStart, kP, kPLabel ? : PSTR("p")) {
}
BlockP(AP_Var_group * group, uint8_t groupStart, float kP,
const prog_char_t * kPLabel = NULL) :
AP_ControllerBlock(group, groupStart, 1),
_kP(group, groupStart, kP, kPLabel ? : PSTR("p")) {
}
float update(const float & input) {
return _kP * input;
}
float update(const float & input) {
return _kP * input;
}
protected:
AP_Float _kP; /// proportional gain
AP_Float _kP; /// proportional gain
};
class BlockI: public AP_ControllerBlock {
public:
BlockI(AP_Var_group * group, uint8_t groupStart, float kI, float iMax,
const prog_char_t * kILabel = NULL,
const prog_char_t * iMaxLabel = NULL) :
AP_ControllerBlock(group, groupStart, 2),
_kI(group, groupStart, kI, kILabel ? : PSTR("i")),
_blockSaturation(group, groupStart + 1, iMax, iMaxLabel ? : PSTR("iMax")),
_eI(0) {
}
BlockI(AP_Var_group * group, uint8_t groupStart, float kI, float iMax,
const prog_char_t * kILabel = NULL,
const prog_char_t * iMaxLabel = NULL) :
AP_ControllerBlock(group, groupStart, 2),
_kI(group, groupStart, kI, kILabel ? : PSTR("i")),
_blockSaturation(group, groupStart + 1, iMax, iMaxLabel ? : PSTR("iMax")),
_eI(0) {
}
float update(const float & input, const float & dt) {
// integral
_eI += input * dt;
_eI = _blockSaturation.update(_eI);
return _kI * _eI;
}
float update(const float & input, const float & dt) {
// integral
_eI += input * dt;
_eI = _blockSaturation.update(_eI);
return _kI * _eI;
}
protected:
AP_Float _kI; /// integral gain
BlockSaturation _blockSaturation; /// integrator saturation
float _eI; /// integral of input
AP_Float _kI; /// integral gain
BlockSaturation _blockSaturation; /// integrator saturation
float _eI; /// integral of input
};
class BlockD: public AP_ControllerBlock {
public:
BlockD(AP_Var_group * group, uint8_t groupStart, float kD, uint8_t dFCut,
const prog_char_t * kDLabel = NULL,
const prog_char_t * dFCutLabel = NULL) :
AP_ControllerBlock(group, groupStart, 2),
_blockLowPass(group, groupStart, dFCut,
dFCutLabel ? : PSTR("dFCut")),
_kD(group, _blockLowPass.getGroupEnd(), kD,
kDLabel ? : PSTR("d")), _eP(0) {
}
float update(const float & input, const float & dt) {
// derivative with low pass
float _eD = _blockLowPass.update((_eP - input) / dt, dt);
// proportional, note must come after derivative
// because derivatve uses _eP as previous value
_eP = input;
return _kD * _eD;
}
BlockD(AP_Var_group * group, uint8_t groupStart, float kD, uint8_t dFCut,
const prog_char_t * kDLabel = NULL,
const prog_char_t * dFCutLabel = NULL) :
AP_ControllerBlock(group, groupStart, 2),
_blockLowPass(group, groupStart, dFCut,
dFCutLabel ? : PSTR("dFCut")),
_kD(group, _blockLowPass.getGroupEnd(), kD,
kDLabel ? : PSTR("d")), _eP(0) {
}
float update(const float & input, const float & dt) {
// derivative with low pass
float _eD = _blockLowPass.update((_eP - input) / dt, dt);
// proportional, note must come after derivative
// because derivatve uses _eP as previous value
_eP = input;
return _kD * _eD;
}
protected:
BlockLowPass _blockLowPass;
AP_Float _kD; /// derivative gain
float _eP; /// input
BlockLowPass _blockLowPass;
AP_Float _kD; /// derivative gain
float _eP; /// input
};
class BlockPID: public AP_ControllerBlock {
public:
BlockPID(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float kD, float iMax, float yMax, uint8_t dFcut) :
AP_ControllerBlock(group, groupStart, 6),
_blockP(group, groupStart, kP),
_blockI(group, _blockP.getGroupEnd(), kI, iMax),
_blockD(group, _blockI.getGroupEnd(), kD, dFcut),
_blockSaturation(group, _blockD.getGroupEnd(), yMax) {
}
BlockPID(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float kD, float iMax, float yMax, uint8_t dFcut) :
AP_ControllerBlock(group, groupStart, 6),
_blockP(group, groupStart, kP),
_blockI(group, _blockP.getGroupEnd(), kI, iMax),
_blockD(group, _blockI.getGroupEnd(), kD, dFcut),
_blockSaturation(group, _blockD.getGroupEnd(), yMax) {
}
float update(const float & input, const float & dt) {
return _blockSaturation.update(
_blockP.update(input) + _blockI.update(input, dt)
+ _blockD.update(input, dt));
}
float update(const float & input, const float & dt) {
return _blockSaturation.update(
_blockP.update(input) + _blockI.update(input, dt)
+ _blockD.update(input, dt));
}
protected:
BlockP _blockP;
BlockI _blockI;
BlockD _blockD;
BlockSaturation _blockSaturation;
BlockP _blockP;
BlockI _blockI;
BlockD _blockD;
BlockSaturation _blockSaturation;
};
class BlockPI: public AP_ControllerBlock {
public:
BlockPI(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float iMax, float yMax) :
AP_ControllerBlock(group, groupStart, 4),
_blockP(group, groupStart, kP),
_blockI(group, _blockP.getGroupEnd(), kI, iMax),
_blockSaturation(group, _blockI.getGroupEnd(), yMax) {
}
BlockPI(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float iMax, float yMax) :
AP_ControllerBlock(group, groupStart, 4),
_blockP(group, groupStart, kP),
_blockI(group, _blockP.getGroupEnd(), kI, iMax),
_blockSaturation(group, _blockI.getGroupEnd(), yMax) {
}
float update(const float & input, const float & dt) {
float update(const float & input, const float & dt) {
float y = _blockP.update(input) + _blockI.update(input, dt);
return _blockSaturation.update(y);
}
float y = _blockP.update(input) + _blockI.update(input, dt);
return _blockSaturation.update(y);
}
protected:
BlockP _blockP;
BlockI _blockI;
BlockSaturation _blockSaturation;
BlockP _blockP;
BlockI _blockI;
BlockSaturation _blockSaturation;
};
class BlockPD: public AP_ControllerBlock {
public:
BlockPD(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float kD, float iMax, float yMax, uint8_t dFcut) :
AP_ControllerBlock(group, groupStart, 4),
_blockP(group, groupStart, kP),
_blockD(group, _blockP.getGroupEnd(), kD, dFcut),
_blockSaturation(group, _blockD.getGroupEnd(), yMax) {
}
BlockPD(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float kD, float iMax, float yMax, uint8_t dFcut) :
AP_ControllerBlock(group, groupStart, 4),
_blockP(group, groupStart, kP),
_blockD(group, _blockP.getGroupEnd(), kD, dFcut),
_blockSaturation(group, _blockD.getGroupEnd(), yMax) {
}
float update(const float & input, const float & dt) {
float update(const float & input, const float & dt) {
float y = _blockP.update(input) + _blockD.update(input, dt);
return _blockSaturation.update(y);
}
float y = _blockP.update(input) + _blockD.update(input, dt);
return _blockSaturation.update(y);
}
protected:
BlockP _blockP;
BlockD _blockD;
BlockSaturation _blockSaturation;
BlockP _blockP;
BlockD _blockD;
BlockSaturation _blockSaturation;
};
/// PID with derivative feedback (ignores reference derivative)
class BlockPIDDfb: public AP_ControllerBlock {
public:
BlockPIDDfb(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float kD, float iMax, float yMax, float dFCut,
const prog_char_t * dFCutLabel = NULL,
const prog_char_t * dLabel = NULL) :
AP_ControllerBlock(group, groupStart, 5),
_blockP(group, groupStart, kP),
_blockI(group, _blockP.getGroupEnd(), kI, iMax),
_blockSaturation(group, _blockI.getGroupEnd(), yMax),
_blockLowPass(group, _blockSaturation.getGroupEnd(), dFCut,
dFCutLabel ? : PSTR("dFCut")),
_kD(group, _blockLowPass.getGroupEnd(), kD, dLabel ? : PSTR("d"))
{
}
float update(const float & input, const float & derivative,
const float & dt) {
float y = _blockP.update(input) + _blockI.update(input, dt) - _kD
* _blockLowPass.update(derivative,dt);
return _blockSaturation.update(y);
}
BlockPIDDfb(AP_Var_group * group, uint8_t groupStart, float kP, float kI,
float kD, float iMax, float yMax, float dFCut,
const prog_char_t * dFCutLabel = NULL,
const prog_char_t * dLabel = NULL) :
AP_ControllerBlock(group, groupStart, 5),
_blockP(group, groupStart, kP),
_blockI(group, _blockP.getGroupEnd(), kI, iMax),
_blockSaturation(group, _blockI.getGroupEnd(), yMax),
_blockLowPass(group, _blockSaturation.getGroupEnd(), dFCut,
dFCutLabel ? : PSTR("dFCut")),
_kD(group, _blockLowPass.getGroupEnd(), kD, dLabel ? : PSTR("d"))
{
}
float update(const float & input, const float & derivative,
const float & dt) {
float y = _blockP.update(input) + _blockI.update(input, dt) - _kD
* _blockLowPass.update(derivative,dt);
return _blockSaturation.update(y);
}
protected:
BlockP _blockP;
BlockI _blockI;
BlockSaturation _blockSaturation;
BlockLowPass _blockLowPass;
AP_Float _kD; /// derivative gain
BlockP _blockP;
BlockI _blockI;
BlockSaturation _blockSaturation;
BlockLowPass _blockLowPass;
AP_Float _kD; /// derivative gain
};
} // apo

View File

@ -15,65 +15,75 @@
namespace apo {
AP_Guide::AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal) :
_navigator(navigator), _hal(hal), _command(AP_MavlinkCommand::home),
_previousCommand(AP_MavlinkCommand::home),
_headingCommand(0), _airSpeedCommand(0),
_groundSpeedCommand(0), _altitudeCommand(0), _pNCmd(0),
_pECmd(0), _pDCmd(0), _mode(MAV_NAV_LOST),
_numberOfCommands(1), _cmdIndex(0), _nextCommandCalls(0),
_nextCommandTimer(0) {
_navigator(navigator), _hal(hal), _command(AP_MavlinkCommand::home),
_previousCommand(AP_MavlinkCommand::home),
_headingCommand(0), _airSpeedCommand(0),
_groundSpeedCommand(0), _altitudeCommand(0), _pNCmd(0),
_pECmd(0), _pDCmd(0), _mode(MAV_NAV_LOST),
_numberOfCommands(1), _cmdIndex(0), _nextCommandCalls(0),
_nextCommandTimer(0) {
}
void AP_Guide::setCurrentIndex(uint8_t val){
_cmdIndex.set_and_save(val);
_command = AP_MavlinkCommand(getCurrentIndex());
_previousCommand = AP_MavlinkCommand(getPreviousIndex());
_hal->gcs->sendMessage(MAVLINK_MSG_ID_WAYPOINT_CURRENT);
void AP_Guide::setCurrentIndex(uint8_t val) {
_cmdIndex.set_and_save(val);
_command = AP_MavlinkCommand(getCurrentIndex());
_previousCommand = AP_MavlinkCommand(getPreviousIndex());
_hal->gcs->sendMessage(MAVLINK_MSG_ID_WAYPOINT_CURRENT);
}
float AP_Guide::getHeadingError() {
float headingError = getHeadingCommand()
- _navigator->getYaw();
if (headingError > 180 * deg2Rad)
headingError -= 360 * deg2Rad;
if (headingError < -180 * deg2Rad)
headingError += 360 * deg2Rad;
return headingError;
}
MavlinkGuide::MavlinkGuide(AP_Navigator * navigator,
AP_HardwareAbstractionLayer * hal) :
AP_Guide(navigator, hal), _rangeFinderFront(), _rangeFinderBack(),
_rangeFinderLeft(), _rangeFinderRight(),
_group(k_guide, PSTR("guide_")),
_velocityCommand(&_group, 1, 1, PSTR("velCmd")),
_crossTrackGain(&_group, 2, 1, PSTR("xt")),
_crossTrackLim(&_group, 3, 90, PSTR("xtLim")) {
AP_HardwareAbstractionLayer * hal, float velCmd, float xt, float xtLim) :
AP_Guide(navigator, hal), _rangeFinderFront(), _rangeFinderBack(),
_rangeFinderLeft(), _rangeFinderRight(),
_group(k_guide, PSTR("guide_")),
_velocityCommand(&_group, 1, velCmd, PSTR("velCmd")),
_crossTrackGain(&_group, 2, xt, PSTR("xt")),
_crossTrackLim(&_group, 3, xtLim, PSTR("xtLim")) {
for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) {
RangeFinder * rF = _hal->rangeFinders[i];
if (rF == NULL)
continue;
if (rF->orientation_x == 1 && rF->orientation_y == 0
&& rF->orientation_z == 0)
_rangeFinderFront = rF;
else if (rF->orientation_x == -1 && rF->orientation_y == 0
&& rF->orientation_z == 0)
_rangeFinderBack = rF;
else if (rF->orientation_x == 0 && rF->orientation_y == 1
&& rF->orientation_z == 0)
_rangeFinderRight = rF;
else if (rF->orientation_x == 0 && rF->orientation_y == -1
&& rF->orientation_z == 0)
_rangeFinderLeft = rF;
for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) {
RangeFinder * rF = _hal->rangeFinders[i];
if (rF == NULL)
continue;
if (rF->orientation_x == 1 && rF->orientation_y == 0
&& rF->orientation_z == 0)
_rangeFinderFront = rF;
else if (rF->orientation_x == -1 && rF->orientation_y == 0
&& rF->orientation_z == 0)
_rangeFinderBack = rF;
else if (rF->orientation_x == 0 && rF->orientation_y == 1
&& rF->orientation_z == 0)
_rangeFinderRight = rF;
else if (rF->orientation_x == 0 && rF->orientation_y == -1
&& rF->orientation_z == 0)
_rangeFinderLeft = rF;
}
}
}
void MavlinkGuide::update() {
// process mavlink commands
handleCommand();
// process mavlink commands
handleCommand();
// obstacle avoidance overrides
// stop if your going to drive into something in front of you
for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++)
_hal->rangeFinders[i]->read();
float frontDistance = _rangeFinderFront->distance / 200.0; //convert for other adc
if (_rangeFinderFront && frontDistance < 2) {
_mode = MAV_NAV_VECTOR;
// obstacle avoidance overrides
// stop if your going to drive into something in front of you
for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++)
_hal->rangeFinders[i]->read();
float frontDistance = _rangeFinderFront->distance / 200.0; //convert for other adc
if (_rangeFinderFront && frontDistance < 2) {
_mode = MAV_NAV_VECTOR;
//airSpeedCommand = 0;
//groundSpeedCommand = 0;
//airSpeedCommand = 0;
//groundSpeedCommand = 0;
// _headingCommand -= 45 * deg2Rad;
// _hal->debug->print("Obstacle Distance (m): ");
// _hal->debug->println(frontDistance);
@ -82,120 +92,120 @@ void MavlinkGuide::update() {
// _hal->debug->printf_P(
// PSTR("Front Distance, %f\n"),
// frontDistance);
}
if (_rangeFinderBack && _rangeFinderBack->distance < 5) {
_airSpeedCommand = 0;
_groundSpeedCommand = 0;
}
if (_rangeFinderBack && _rangeFinderBack->distance < 5) {
_airSpeedCommand = 0;
_groundSpeedCommand = 0;
}
}
if (_rangeFinderLeft && _rangeFinderLeft->distance < 5) {
_airSpeedCommand = 0;
_groundSpeedCommand = 0;
}
if (_rangeFinderLeft && _rangeFinderLeft->distance < 5) {
_airSpeedCommand = 0;
_groundSpeedCommand = 0;
}
if (_rangeFinderRight && _rangeFinderRight->distance < 5) {
_airSpeedCommand = 0;
_groundSpeedCommand = 0;
}
if (_rangeFinderRight && _rangeFinderRight->distance < 5) {
_airSpeedCommand = 0;
_groundSpeedCommand = 0;
}
}
void MavlinkGuide::nextCommand() {
// within 1 seconds, check if more than 5 calls to next command occur
// if they do, go to home waypoint
if (millis() - _nextCommandTimer < 1000) {
if (_nextCommandCalls > 5) {
Serial.println("commands loading too fast, returning home");
setCurrentIndex(0);
setNumberOfCommands(1);
_nextCommandCalls = 0;
_nextCommandTimer = millis();
return;
}
_nextCommandCalls++;
} else {
_nextCommandTimer = millis();
_nextCommandCalls = 0;
}
// within 1 seconds, check if more than 5 calls to next command occur
// if they do, go to home waypoint
if (millis() - _nextCommandTimer < 1000) {
if (_nextCommandCalls > 5) {
Serial.println("commands loading too fast, returning home");
setCurrentIndex(0);
setNumberOfCommands(1);
_nextCommandCalls = 0;
_nextCommandTimer = millis();
return;
}
_nextCommandCalls++;
} else {
_nextCommandTimer = millis();
_nextCommandCalls = 0;
}
_cmdIndex = getNextIndex();
//Serial.print("cmd : "); Serial.println(int(_cmdIndex));
//Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex()));
//Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands()));
_command = AP_MavlinkCommand(getCurrentIndex());
_previousCommand = AP_MavlinkCommand(getPreviousIndex());
_cmdIndex = getNextIndex();
//Serial.print("cmd : "); Serial.println(int(_cmdIndex));
//Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex()));
//Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands()));
_command = AP_MavlinkCommand(getCurrentIndex());
_previousCommand = AP_MavlinkCommand(getPreviousIndex());
}
void MavlinkGuide::handleCommand() {
// TODO handle more commands
switch (_command.getCommand()) {
// TODO handle more commands
switch (_command.getCommand()) {
case MAV_CMD_NAV_WAYPOINT: {
case MAV_CMD_NAV_WAYPOINT: {
// if we don't have enough waypoint for cross track calcs
// go home
if (_numberOfCommands == 1) {
_mode = MAV_NAV_RETURNING;
_altitudeCommand = AP_MavlinkCommand::home.getAlt();
_headingCommand = AP_MavlinkCommand::home.bearingTo(
_navigator->getLat_degInt(), _navigator->getLon_degInt())
+ 180 * deg2Rad;
if (_headingCommand > 360 * deg2Rad)
_headingCommand -= 360 * deg2Rad;
// if we don't have enough waypoint for cross track calcs
// go home
if (_numberOfCommands == 1) {
_mode = MAV_NAV_RETURNING;
_altitudeCommand = AP_MavlinkCommand::home.getAlt();
_headingCommand = AP_MavlinkCommand::home.bearingTo(
_navigator->getLat_degInt(), _navigator->getLon_degInt())
+ 180 * deg2Rad;
if (_headingCommand > 360 * deg2Rad)
_headingCommand -= 360 * deg2Rad;
//_hal->debug->printf_P(PSTR("going home: bearing: %f distance: %f\n"),
//headingCommand,AP_MavlinkCommand::home.distanceTo(_navigator->getLat_degInt(),_navigator->getLon_degInt()));
// if we have 2 or more waypoints do x track navigation
} else {
_mode = MAV_NAV_WAYPOINT;
float alongTrack = _command.alongTrack(_previousCommand,
_navigator->getLat_degInt(),
_navigator->getLon_degInt());
float distanceToNext = _command.distanceTo(
_navigator->getLat_degInt(), _navigator->getLon_degInt());
float segmentLength = _previousCommand.distanceTo(_command);
if (distanceToNext < _command.getRadius() || alongTrack
> segmentLength)
{
Serial.println("waypoint reached");
nextCommand();
}
_altitudeCommand = _command.getAlt();
float dXt = _command.crossTrack(_previousCommand,
_navigator->getLat_degInt(),
_navigator->getLon_degInt());
float temp = dXt * _crossTrackGain * deg2Rad; // crosstrack gain, rad/m
if (temp > _crossTrackLim * deg2Rad)
temp = _crossTrackLim * deg2Rad;
if (temp < -_crossTrackLim * deg2Rad)
temp = -_crossTrackLim * deg2Rad;
float bearing = _previousCommand.bearingTo(_command);
_headingCommand = bearing - temp;
//_hal->debug->printf_P(
//PSTR("nav: bCurrent2Dest: %f\tdXt: %f\tcmdHeading: %f\tnextWpDistance: %f\talongTrack: %f\n"),
//bearing * rad2Deg, dXt, _headingCommand * rad2Deg, distanceToNext, alongTrack);
}
//_hal->debug->printf_P(PSTR("going home: bearing: %f distance: %f\n"),
//headingCommand,AP_MavlinkCommand::home.distanceTo(_navigator->getLat_degInt(),_navigator->getLon_degInt()));
_groundSpeedCommand = _velocityCommand;
// if we have 2 or more waypoints do x track navigation
} else {
_mode = MAV_NAV_WAYPOINT;
float alongTrack = _command.alongTrack(_previousCommand,
_navigator->getLat_degInt(),
_navigator->getLon_degInt());
float distanceToNext = _command.distanceTo(
_navigator->getLat_degInt(), _navigator->getLon_degInt());
float segmentLength = _previousCommand.distanceTo(_command);
if (distanceToNext < _command.getRadius() || alongTrack
> segmentLength)
{
Serial.println("waypoint reached");
nextCommand();
}
_altitudeCommand = _command.getAlt();
float dXt = _command.crossTrack(_previousCommand,
_navigator->getLat_degInt(),
_navigator->getLon_degInt());
float temp = dXt * _crossTrackGain * deg2Rad; // crosstrack gain, rad/m
if (temp > _crossTrackLim * deg2Rad)
temp = _crossTrackLim * deg2Rad;
if (temp < -_crossTrackLim * deg2Rad)
temp = -_crossTrackLim * deg2Rad;
float bearing = _previousCommand.bearingTo(_command);
_headingCommand = bearing - temp;
//_hal->debug->printf_P(
//PSTR("nav: bCurrent2Dest: %f\tdXt: %f\tcmdHeading: %f\tnextWpDistance: %f\talongTrack: %f\n"),
//bearing * rad2Deg, dXt, _headingCommand * rad2Deg, distanceToNext, alongTrack);
}
// calculate pN,pE,pD from home and gps coordinates
_pNCmd = _command.getPN(_navigator->getLat_degInt(),
_navigator->getLon_degInt());
_pECmd = _command.getPE(_navigator->getLat_degInt(),
_navigator->getLon_degInt());
_pDCmd = _command.getPD(_navigator->getAlt_intM());
_groundSpeedCommand = _velocityCommand;
// debug
//_hal->debug->printf_P(
//PSTR("guide loop, number: %d, current index: %d, previous index: %d\n"),
//getNumberOfCommands(),
//getCurrentIndex(),
//getPreviousIndex());
// calculate pN,pE,pD from home and gps coordinates
_pNCmd = _command.getPN(_navigator->getLat_degInt(),
_navigator->getLon_degInt());
_pECmd = _command.getPE(_navigator->getLat_degInt(),
_navigator->getLon_degInt());
_pDCmd = _command.getPD(_navigator->getAlt_intM());
break;
}
// debug
//_hal->debug->printf_P(
//PSTR("guide loop, number: %d, current index: %d, previous index: %d\n"),
//getNumberOfCommands(),
//getCurrentIndex(),
//getPreviousIndex());
break;
}
// case MAV_CMD_CONDITION_CHANGE_ALT:
// case MAV_CMD_CONDITION_DELAY:
// case MAV_CMD_CONDITION_DISTANCE:
@ -224,12 +234,12 @@ void MavlinkGuide::handleCommand() {
// case MAV_CMD_NAV_PATHPLANNING:
// case MAV_CMD_NAV_RETURN_TO_LAUNCH:
// case MAV_CMD_NAV_TAKEOFF:
default:
// unhandled command, skip
Serial.println("unhandled command");
nextCommand();
break;
}
default:
// unhandled command, skip
Serial.println("unhandled command");
nextCommand();
break;
}
}
} // namespace apo

View File

@ -33,116 +33,117 @@ class AP_HardwareAbstractionLayer;
class AP_Guide {
public:
/**
* This is the constructor, which requires a link to the navigator.
* @param navigator This is the navigator pointer.
*/
AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal);
/**
* This is the constructor, which requires a link to the navigator.
* @param navigator This is the navigator pointer.
*/
AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal);
virtual void update() = 0;
virtual void update() = 0;
virtual void nextCommand() = 0;
virtual void nextCommand() = 0;
MAV_NAV getMode() const {
return _mode;
}
uint8_t getCurrentIndex() {
return _cmdIndex;
}
MAV_NAV getMode() const {
return _mode;
}
uint8_t getCurrentIndex() {
return _cmdIndex;
}
void setCurrentIndex(uint8_t val);
void setCurrentIndex(uint8_t val);
uint8_t getNumberOfCommands() {
return _numberOfCommands;
}
uint8_t getNumberOfCommands() {
return _numberOfCommands;
}
void setNumberOfCommands(uint8_t val) {
_numberOfCommands.set_and_save(val);
}
void setNumberOfCommands(uint8_t val) {
_numberOfCommands.set_and_save(val);
}
uint8_t getPreviousIndex() {
// find previous waypoint, TODO, handle non-nav commands
int16_t prevIndex = int16_t(getCurrentIndex()) - 1;
if (prevIndex < 0)
prevIndex = getNumberOfCommands() - 1;
return (uint8_t) prevIndex;
}
uint8_t getPreviousIndex() {
// find previous waypoint, TODO, handle non-nav commands
int16_t prevIndex = int16_t(getCurrentIndex()) - 1;
if (prevIndex < 0)
prevIndex = getNumberOfCommands() - 1;
return (uint8_t) prevIndex;
}
uint8_t getNextIndex() {
// find previous waypoint, TODO, handle non-nav commands
int16_t nextIndex = int16_t(getCurrentIndex()) + 1;
if (nextIndex > (getNumberOfCommands() - 1))
nextIndex = 0;
return nextIndex;
}
uint8_t getNextIndex() {
// find previous waypoint, TODO, handle non-nav commands
int16_t nextIndex = int16_t(getCurrentIndex()) + 1;
if (nextIndex > (getNumberOfCommands() - 1))
nextIndex = 0;
return nextIndex;
}
float getHeadingCommand() {
return _headingCommand;
}
float getAirSpeedCommand() {
return _airSpeedCommand;
}
float getGroundSpeedCommand() {
return _groundSpeedCommand;
}
float getAltitudeCommand() {
return _altitudeCommand;
}
float getPNCmd() {
return _pNCmd;
}
float getPECmd() {
return _pECmd;
}
float getPDCmd() {
return _pDCmd;
}
MAV_NAV getMode() {
return _mode;
}
uint8_t getCommandIndex() {
return _cmdIndex;
}
float getHeadingError();
float getHeadingCommand() {
return _headingCommand;
}
float getAirSpeedCommand() {
return _airSpeedCommand;
}
float getGroundSpeedCommand() {
return _groundSpeedCommand;
}
float getAltitudeCommand() {
return _altitudeCommand;
}
float getPNCmd() {
return _pNCmd;
}
float getPECmd() {
return _pECmd;
}
float getPDCmd() {
return _pDCmd;
}
MAV_NAV getMode() {
return _mode;
}
uint8_t getCommandIndex() {
return _cmdIndex;
}
protected:
AP_Navigator * _navigator;
AP_HardwareAbstractionLayer * _hal;
AP_MavlinkCommand _command, _previousCommand;
float _headingCommand;
float _airSpeedCommand;
float _groundSpeedCommand;
float _altitudeCommand;
float _pNCmd;
float _pECmd;
float _pDCmd;
MAV_NAV _mode;
AP_Uint8 _numberOfCommands;
AP_Uint8 _cmdIndex;
uint16_t _nextCommandCalls;
uint16_t _nextCommandTimer;
AP_Navigator * _navigator;
AP_HardwareAbstractionLayer * _hal;
AP_MavlinkCommand _command, _previousCommand;
float _headingCommand;
float _airSpeedCommand;
float _groundSpeedCommand;
float _altitudeCommand;
float _pNCmd;
float _pECmd;
float _pDCmd;
MAV_NAV _mode;
AP_Uint8 _numberOfCommands;
AP_Uint8 _cmdIndex;
uint16_t _nextCommandCalls;
uint16_t _nextCommandTimer;
};
class MavlinkGuide: public AP_Guide {
public:
MavlinkGuide(AP_Navigator * navigator,
AP_HardwareAbstractionLayer * hal);
virtual void update();
void nextCommand();
void handleCommand();
MavlinkGuide(AP_Navigator * navigator,
AP_HardwareAbstractionLayer * hal, float velCmd, float xt, float xtLim);
virtual void update();
void nextCommand();
void handleCommand();
private:
RangeFinder * _rangeFinderFront;
RangeFinder * _rangeFinderBack;
RangeFinder * _rangeFinderLeft;
RangeFinder * _rangeFinderRight;
AP_Var_group _group;
AP_Float _velocityCommand;
AP_Float _crossTrackGain;
AP_Float _crossTrackLim;
RangeFinder * _rangeFinderFront;
RangeFinder * _rangeFinderBack;
RangeFinder * _rangeFinderLeft;
RangeFinder * _rangeFinderRight;
AP_Var_group _group;
AP_Float _velocityCommand;
AP_Float _crossTrackGain;
AP_Float _crossTrackLim;
};
} // namespace apo
#endif // AP_Guide_H
// vim:ts=4:sw=4:expandtab

View File

@ -6,3 +6,4 @@
*/
#include "AP_HardwareAbstractionLayer.h"
// vim:ts=4:sw=4:expandtab

View File

@ -28,134 +28,149 @@ class AP_BatteryMonitor;
// enumerations
enum halMode_t {
MODE_LIVE, MODE_HIL_CNTL,
/*MODE_HIL_NAV*/};
MODE_LIVE, MODE_HIL_CNTL,
/*MODE_HIL_NAV*/
};
enum board_t {
BOARD_ARDUPILOTMEGA_1280, BOARD_ARDUPILOTMEGA_2560, BOARD_ARDUPILOTMEGA_2
BOARD_ARDUPILOTMEGA_1280, BOARD_ARDUPILOTMEGA_2560, BOARD_ARDUPILOTMEGA_2
};
enum vehicle_t {
VEHICLE_CAR, VEHICLE_QUAD, VEHICLE_PLANE, VEHICLE_BOAT, VEHICLE_TANK
VEHICLE_CAR, VEHICLE_QUAD, VEHICLE_PLANE, VEHICLE_BOAT, VEHICLE_TANK
};
class AP_HardwareAbstractionLayer {
public:
// default ctors on pointers called on pointers here, this
// allows NULL to be used as a boolean for if the device was
// initialized
AP_HardwareAbstractionLayer(halMode_t mode, board_t board,
vehicle_t vehicle, uint8_t heartBeatTimeout) :
adc(), gps(), baro(), compass(), rangeFinders(), imu(), batteryMonitor(), rc(), gcs(),
hil(), debug(), load(), lastHeartBeat(),
_heartBeatTimeout(heartBeatTimeout), _mode(mode),
_board(board), _vehicle(vehicle), _state(MAV_STATE_UNINIT) {
// default ctors on pointers called on pointers here, this
// allows NULL to be used as a boolean for if the device was
// initialized
AP_HardwareAbstractionLayer(halMode_t mode, board_t board,
vehicle_t vehicle, uint8_t heartBeatTimeout) :
adc(), gps(), baro(), compass(), rangeFinders(), imu(), batteryMonitor(), rc(), gcs(),
hil(), debug(), load(), lastHeartBeat(),
_heartBeatTimeout(heartBeatTimeout), _mode(mode),
_board(board), _vehicle(vehicle), _state(MAV_STATE_UNINIT) {
/*
* Board specific hardware initialization
*/
if (board == BOARD_ARDUPILOTMEGA_1280) {
slideSwitchPin = 40;
pushButtonPin = 41;
aLedPin = 37;
bLedPin = 36;
cLedPin = 35;
eepromMaxAddr = 1024;
pinMode(aLedPin, OUTPUT); // extra led
pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink;
pinMode(cLedPin, OUTPUT); // gps led
pinMode(slideSwitchPin, INPUT);
pinMode(pushButtonPin, INPUT);
DDRL |= B00000100; // set port L, pint 2 to output for the relay
} else if (board == BOARD_ARDUPILOTMEGA_2560) {
slideSwitchPin = 40;
pushButtonPin = 41;
aLedPin = 37;
bLedPin = 36;
cLedPin = 35;
eepromMaxAddr = 2048;
pinMode(aLedPin, OUTPUT); // extra led
pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink;
pinMode(cLedPin, OUTPUT); // gps led
pinMode(slideSwitchPin, INPUT);
pinMode(pushButtonPin, INPUT);
DDRL |= B00000100; // set port L, pint 2 to output for the relay
}
}
/*
* Board specific hardware initialization
*/
if (board == BOARD_ARDUPILOTMEGA_1280) {
slideSwitchPin = 40;
pushButtonPin = 41;
aLedPin = 37;
bLedPin = 36;
cLedPin = 35;
eepromMaxAddr = 1024;
pinMode(aLedPin, OUTPUT); // extra led
pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink;
pinMode(cLedPin, OUTPUT); // gps led
pinMode(slideSwitchPin, INPUT);
pinMode(pushButtonPin, INPUT);
DDRL |= B00000100; // set port L, pint 2 to output for the relay
} else if (board == BOARD_ARDUPILOTMEGA_2560) {
slideSwitchPin = 40;
pushButtonPin = 41;
aLedPin = 37;
bLedPin = 36;
cLedPin = 35;
eepromMaxAddr = 2048;
pinMode(aLedPin, OUTPUT); // extra led
pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink;
pinMode(cLedPin, OUTPUT); // gps led
pinMode(slideSwitchPin, INPUT);
pinMode(pushButtonPin, INPUT);
DDRL |= B00000100; // set port L, pint 2 to output for the relay
} else if (board == BOARD_ARDUPILOTMEGA_2) {
slideSwitchPin = 40;
pushButtonPin = 41;
aLedPin = 37;
bLedPin = 36;
cLedPin = 35;
eepromMaxAddr = 2048;
pinMode(aLedPin, OUTPUT); // extra led
pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink;
pinMode(cLedPin, OUTPUT); // gps led
pinMode(slideSwitchPin, INPUT);
pinMode(pushButtonPin, INPUT);
DDRL |= B00000100; // set port L, pint 2 to output for the relay
}
}
/**
* Sensors
*/
AP_ADC * adc;
GPS * gps;
APM_BMP085_Class * baro;
Compass * compass;
Vector<RangeFinder *> rangeFinders;
IMU * imu;
AP_BatteryMonitor * batteryMonitor;
/**
* Sensors
*/
AP_ADC * adc;
GPS * gps;
APM_BMP085_Class * baro;
Compass * compass;
Vector<RangeFinder *> rangeFinders;
IMU * imu;
AP_BatteryMonitor * batteryMonitor;
/**
* Radio Channels
*/
Vector<AP_RcChannel *> rc;
/**
* Radio Channels
*/
Vector<AP_RcChannel *> rc;
/**
* Communication Channels
*/
AP_CommLink * gcs;
AP_CommLink * hil;
FastSerial * debug;
/**
* Communication Channels
*/
AP_CommLink * gcs;
AP_CommLink * hil;
FastSerial * debug;
/**
* data
*/
uint8_t load;
uint32_t lastHeartBeat;
/**
* data
*/
uint8_t load;
uint32_t lastHeartBeat;
/**
* settings
*/
uint8_t slideSwitchPin;
uint8_t pushButtonPin;
uint8_t aLedPin;
uint8_t bLedPin;
uint8_t cLedPin;
uint16_t eepromMaxAddr;
/**
* settings
*/
uint8_t slideSwitchPin;
uint8_t pushButtonPin;
uint8_t aLedPin;
uint8_t bLedPin;
uint8_t cLedPin;
uint16_t eepromMaxAddr;
// accessors
halMode_t getMode() {
return _mode;
}
board_t getBoard() {
return _board;
}
vehicle_t getVehicle() {
return _vehicle;
}
MAV_STATE getState() {
return _state;
}
void setState(MAV_STATE state) {
_state = state;
}
// accessors
halMode_t getMode() {
return _mode;
}
board_t getBoard() {
return _board;
}
vehicle_t getVehicle() {
return _vehicle;
}
MAV_STATE getState() {
return _state;
}
void setState(MAV_STATE state) {
_state = state;
}
bool heartBeatLost() {
if (_heartBeatTimeout == 0)
return false;
else
return ((micros() - lastHeartBeat) / 1e6) > _heartBeatTimeout;
}
bool heartBeatLost() {
if (_heartBeatTimeout == 0)
return false;
else
return ((micros() - lastHeartBeat) / 1e6) > _heartBeatTimeout;
}
private:
// enumerations
uint8_t _heartBeatTimeout;
halMode_t _mode;
board_t _board;
vehicle_t _vehicle;
MAV_STATE _state;
// enumerations
uint8_t _heartBeatTimeout;
halMode_t _mode;
board_t _board;
vehicle_t _vehicle;
MAV_STATE _state;
};
}
} // namespace apo
#endif /* AP_HARDWAREABSTRACTIONLAYER_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -5,183 +5,205 @@
* Author: jgoppert
*/
#include "../FastSerial/FastSerial.h"
#include "AP_MavlinkCommand.h"
namespace apo {
AP_MavlinkCommand::AP_MavlinkCommand(const AP_MavlinkCommand & v) :
_data(v._data), _seq(v._seq) {
//if (FastSerial::getInitialized(0)) Serial.println("copy ctor");
_data(v._data), _seq(v._seq) {
//if (FastSerial::getInitialized(0)) Serial.println("copy ctor");
}
AP_MavlinkCommand::AP_MavlinkCommand(uint16_t index, bool doLoad) :
_data(k_commands + index), _seq(index) {
_data(k_commands + index), _seq(index) {
if (FastSerial::getInitialized(0)) {
Serial.println("index ctor");
Serial.println("++");
Serial.print("index: "); Serial.println(index);
Serial.print("key: "); Serial.println(k_commands + index);
Serial.println("++");
}
if (FastSerial::getInitialized(0)) {
Serial.println("index ctor");
Serial.println("++");
Serial.print("index: ");
Serial.println(index);
Serial.print("key: ");
Serial.println(k_commands + index);
Serial.println("++");
}
// default values for structure
_data.get().command = MAV_CMD_NAV_WAYPOINT;
_data.get().autocontinue = true;
_data.get().frame = MAV_FRAME_GLOBAL;
_data.get().param1 = 0;
_data.get().param2 = 10; // radius of 10 meters
_data.get().param3 = 0;
_data.get().param4 = 0;
_data.get().x = 0;
_data.get().y = 0;
_data.get().z = 1000;
// default values for structure
_data.get().command = MAV_CMD_NAV_WAYPOINT;
_data.get().autocontinue = true;
_data.get().frame = MAV_FRAME_GLOBAL;
_data.get().param1 = 0;
_data.get().param2 = 10; // radius of 10 meters
_data.get().param3 = 0;
_data.get().param4 = 0;
_data.get().x = 0;
_data.get().y = 0;
_data.get().z = 1000;
// This is a failsafe measure to stop trying to load a command if it can't load
if (doLoad && !load()) {
Serial.println("load failed, reverting to home waypoint");
_data = AP_MavlinkCommand::home._data;
_seq = AP_MavlinkCommand::home._seq;
}
// This is a failsafe measure to stop trying to load a command if it can't load
if (doLoad && !load()) {
Serial.println("load failed, reverting to home waypoint");
_data = AP_MavlinkCommand::home._data;
_seq = AP_MavlinkCommand::home._seq;
}
}
AP_MavlinkCommand::AP_MavlinkCommand(const mavlink_waypoint_t & cmd) :
_data(k_commands + cmd.seq), _seq(cmd.seq) {
setCommand(MAV_CMD(cmd.command));
setAutocontinue(cmd.autocontinue);
setFrame(MAV_FRAME(cmd.frame));
setParam1(cmd.param1);
setParam2(cmd.param2);
setParam3(cmd.param3);
setParam4(cmd.param4);
setX(cmd.x);
setY(cmd.y);
setZ(cmd.z);
save();
_data(k_commands + cmd.seq), _seq(cmd.seq) {
setCommand(MAV_CMD(cmd.command));
setAutocontinue(cmd.autocontinue);
setFrame(MAV_FRAME(cmd.frame));
setParam1(cmd.param1);
setParam2(cmd.param2);
setParam3(cmd.param3);
setParam4(cmd.param4);
setX(cmd.x);
setY(cmd.y);
setZ(cmd.z);
save();
// reload home if sent
if (cmd.seq == 0) home.load();
// reload home if sent
if (cmd.seq == 0) home.load();
Serial.println("============================================================");
Serial.println("storing new command from mavlink_waypoint_t");
Serial.print("key: "); Serial.println(_data.key(),DEC);
Serial.print("number: "); Serial.println(cmd.seq,DEC);
Serial.print("command: "); Serial.println(getCommand());
Serial.print("autocontinue: "); Serial.println(getAutocontinue(),DEC);
Serial.print("frame: "); Serial.println(getFrame(),DEC);
Serial.print("1000*param1: "); Serial.println(int(1000*getParam1()),DEC);
Serial.print("1000*param2: "); Serial.println(int(1000*getParam2()),DEC);
Serial.print("1000*param3: "); Serial.println(int(1000*getParam3()),DEC);
Serial.print("1000*param4: "); Serial.println(int(1000*getParam4()),DEC);
Serial.print("1000*x0: "); Serial.println(int(1000*cmd.x),DEC);
Serial.print("1000*y0: "); Serial.println(int(1000*cmd.y),DEC);
Serial.print("1000*z0: "); Serial.println(int(1000*cmd.z),DEC);
Serial.print("1000*x: "); Serial.println(int(1000*getX()),DEC);
Serial.print("1000*y: "); Serial.println(int(1000*getY()),DEC);
Serial.print("1000*z: "); Serial.println(int(1000*getZ()),DEC);
Serial.println("============================================================");
Serial.println("storing new command from mavlink_waypoint_t");
Serial.print("key: ");
Serial.println(_data.key(),DEC);
Serial.print("number: ");
Serial.println(cmd.seq,DEC);
Serial.print("command: ");
Serial.println(getCommand());
Serial.print("autocontinue: ");
Serial.println(getAutocontinue(),DEC);
Serial.print("frame: ");
Serial.println(getFrame(),DEC);
Serial.print("1000*param1: ");
Serial.println(int(1000*getParam1()),DEC);
Serial.print("1000*param2: ");
Serial.println(int(1000*getParam2()),DEC);
Serial.print("1000*param3: ");
Serial.println(int(1000*getParam3()),DEC);
Serial.print("1000*param4: ");
Serial.println(int(1000*getParam4()),DEC);
Serial.print("1000*x0: ");
Serial.println(int(1000*cmd.x),DEC);
Serial.print("1000*y0: ");
Serial.println(int(1000*cmd.y),DEC);
Serial.print("1000*z0: ");
Serial.println(int(1000*cmd.z),DEC);
Serial.print("1000*x: ");
Serial.println(int(1000*getX()),DEC);
Serial.print("1000*y: ");
Serial.println(int(1000*getY()),DEC);
Serial.print("1000*z: ");
Serial.println(int(1000*getZ()),DEC);
load();
load();
Serial.print("1000*x1: "); Serial.println(int(1000*getX()),DEC);
Serial.print("1000*y1: "); Serial.println(int(1000*getY()),DEC);
Serial.print("1000*z1: "); Serial.println(int(1000*getZ()),DEC);
Serial.println("============================================================");
Serial.flush();
Serial.print("1000*x1: ");
Serial.println(int(1000*getX()),DEC);
Serial.print("1000*y1: ");
Serial.println(int(1000*getY()),DEC);
Serial.print("1000*z1: ");
Serial.println(int(1000*getZ()),DEC);
Serial.println("============================================================");
Serial.flush();
}
mavlink_waypoint_t AP_MavlinkCommand::convert(uint8_t current) const {
mavlink_waypoint_t mavCmd;
mavCmd.seq = getSeq();
mavCmd.command = getCommand();
mavCmd.frame = getFrame();
mavCmd.param1 = getParam1();
mavCmd.param2 = getParam2();
mavCmd.param3 = getParam3();
mavCmd.param4 = getParam4();
mavCmd.x = getX();
mavCmd.y = getY();
mavCmd.z = getZ();
mavCmd.autocontinue = getAutocontinue();
mavCmd.current = (getSeq() == current);
mavCmd.target_component = mavlink_system.compid;
mavCmd.target_system = mavlink_system.sysid;
return mavCmd;
mavlink_waypoint_t mavCmd;
mavCmd.seq = getSeq();
mavCmd.command = getCommand();
mavCmd.frame = getFrame();
mavCmd.param1 = getParam1();
mavCmd.param2 = getParam2();
mavCmd.param3 = getParam3();
mavCmd.param4 = getParam4();
mavCmd.x = getX();
mavCmd.y = getY();
mavCmd.z = getZ();
mavCmd.autocontinue = getAutocontinue();
mavCmd.current = (getSeq() == current);
mavCmd.target_component = mavlink_system.compid;
mavCmd.target_system = mavlink_system.sysid;
return mavCmd;
}
float AP_MavlinkCommand::bearingTo(const AP_MavlinkCommand & next) const {
float deltaLon = next.getLon() - getLon();
/*
Serial.print("Lon: "); Serial.println(getLon());
Serial.print("nextLon: "); Serial.println(next.getLon());
Serial.print("deltaLonDeg * 1e7: "); Serial.println(deltaLon*rad2DegInt);
*/
float bearing = atan2(
sin(deltaLon) * cos(next.getLat()),
cos(getLat()) * sin(next.getLat()) - sin(getLat()) * cos(
next.getLat()) * cos(deltaLon));
return bearing;
float deltaLon = next.getLon() - getLon();
/*
Serial.print("Lon: "); Serial.println(getLon());
Serial.print("nextLon: "); Serial.println(next.getLon());
Serial.print("deltaLonDeg * 1e7: "); Serial.println(deltaLon*rad2DegInt);
*/
float bearing = atan2(
sin(deltaLon) * cos(next.getLat()),
cos(getLat()) * sin(next.getLat()) - sin(getLat()) * cos(
next.getLat()) * cos(deltaLon));
return bearing;
}
float AP_MavlinkCommand::bearingTo(int32_t latDegInt, int32_t lonDegInt) const {
// have to be careful to maintain the precision of the gps coordinate
float deltaLon = (lonDegInt - getLon_degInt()) * degInt2Rad;
float nextLat = latDegInt * degInt2Rad;
float bearing = atan2(
sin(deltaLon) * cos(nextLat),
cos(getLat()) * sin(nextLat) - sin(getLat()) * cos(nextLat)
* cos(deltaLon));
if (bearing < 0)
bearing += 2 * M_PI;
return bearing;
// have to be careful to maintain the precision of the gps coordinate
float deltaLon = (lonDegInt - getLon_degInt()) * degInt2Rad;
float nextLat = latDegInt * degInt2Rad;
float bearing = atan2(
sin(deltaLon) * cos(nextLat),
cos(getLat()) * sin(nextLat) - sin(getLat()) * cos(nextLat)
* cos(deltaLon));
if (bearing < 0)
bearing += 2 * M_PI;
return bearing;
}
float AP_MavlinkCommand::distanceTo(const AP_MavlinkCommand & next) const {
float sinDeltaLat2 = sin((getLat() - next.getLat()) / 2);
float sinDeltaLon2 = sin((getLon() - next.getLon()) / 2);
float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos(
next.getLat()) * sinDeltaLon2 * sinDeltaLon2;
float c = 2 * atan2(sqrt(a), sqrt(1 - a));
return rEarth * c;
float sinDeltaLat2 = sin((getLat() - next.getLat()) / 2);
float sinDeltaLon2 = sin((getLon() - next.getLon()) / 2);
float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos(
next.getLat()) * sinDeltaLon2 * sinDeltaLon2;
float c = 2 * atan2(sqrt(a), sqrt(1 - a));
return rEarth * c;
}
float AP_MavlinkCommand::distanceTo(int32_t lat_degInt, int32_t lon_degInt) const {
float sinDeltaLat2 = sin(
(lat_degInt - getLat_degInt()) * degInt2Rad / 2);
float sinDeltaLon2 = sin(
(lon_degInt - getLon_degInt()) * degInt2Rad / 2);
float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos(
lat_degInt * degInt2Rad) * sinDeltaLon2 * sinDeltaLon2;
float c = 2 * atan2(sqrt(a), sqrt(1 - a));
/*
Serial.print("wp lat_degInt: "); Serial.println(getLat_degInt());
Serial.print("wp lon_degInt: "); Serial.println(getLon_degInt());
Serial.print("lat_degInt: "); Serial.println(lat_degInt);
Serial.print("lon_degInt: "); Serial.println(lon_degInt);
Serial.print("sinDeltaLat2: "); Serial.println(sinDeltaLat2);
Serial.print("sinDeltaLon2: "); Serial.println(sinDeltaLon2);
*/
return rEarth * c;
float sinDeltaLat2 = sin(
(lat_degInt - getLat_degInt()) * degInt2Rad / 2);
float sinDeltaLon2 = sin(
(lon_degInt - getLon_degInt()) * degInt2Rad / 2);
float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos(
lat_degInt * degInt2Rad) * sinDeltaLon2 * sinDeltaLon2;
float c = 2 * atan2(sqrt(a), sqrt(1 - a));
/*
Serial.print("wp lat_degInt: "); Serial.println(getLat_degInt());
Serial.print("wp lon_degInt: "); Serial.println(getLon_degInt());
Serial.print("lat_degInt: "); Serial.println(lat_degInt);
Serial.print("lon_degInt: "); Serial.println(lon_degInt);
Serial.print("sinDeltaLat2: "); Serial.println(sinDeltaLat2);
Serial.print("sinDeltaLon2: "); Serial.println(sinDeltaLon2);
*/
return rEarth * c;
}
//calculates cross track of a current location
float AP_MavlinkCommand::crossTrack(const AP_MavlinkCommand & previous,
int32_t lat_degInt, int32_t lon_degInt) const {
float d = previous.distanceTo(lat_degInt, lon_degInt);
float bCurrent = previous.bearingTo(lat_degInt, lon_degInt);
float bNext = previous.bearingTo(*this);
return asin(sin(d / rEarth) * sin(bCurrent - bNext)) * rEarth;
int32_t lat_degInt, int32_t lon_degInt) const {
float d = previous.distanceTo(lat_degInt, lon_degInt);
float bCurrent = previous.bearingTo(lat_degInt, lon_degInt);
float bNext = previous.bearingTo(*this);
return asin(sin(d / rEarth) * sin(bCurrent - bNext)) * rEarth;
}
// calculates along track distance of a current location
float AP_MavlinkCommand::alongTrack(const AP_MavlinkCommand & previous,
int32_t lat_degInt, int32_t lon_degInt) const {
// ignores lat/lon since single prec.
float dXt = this->crossTrack(previous,lat_degInt, lon_degInt);
float d = previous.distanceTo(lat_degInt, lon_degInt);
return dXt / tan(asin(dXt / d));
int32_t lat_degInt, int32_t lon_degInt) const {
// ignores lat/lon since single prec.
float dXt = this->crossTrack(previous,lat_degInt, lon_degInt);
float d = previous.distanceTo(lat_degInt, lon_degInt);
return dXt / tan(asin(dXt / d));
}
AP_MavlinkCommand AP_MavlinkCommand::home = AP_MavlinkCommand(0,false);
}
} // namespace apo
// vim:ts=4:sw=4:expandtab

View File

@ -12,364 +12,364 @@
#include "../AP_Common/AP_Common.h"
#include "AP_Var_keys.h"
#include "constants.h"
#include "../FastSerial/FastSerial.h"
namespace apo {
class AP_MavlinkCommand {
private:
struct CommandStorage {
MAV_CMD command;
bool autocontinue;
MAV_FRAME frame;
float param1;
float param2;
float param3;
float param4;
float x;
float y;
float z;
};
AP_VarS<CommandStorage> _data;
uint16_t _seq;
struct CommandStorage {
MAV_CMD command;
bool autocontinue;
MAV_FRAME frame;
float param1;
float param2;
float param3;
float param4;
float x;
float y;
float z;
};
AP_VarS<CommandStorage> _data;
uint16_t _seq;
public:
static AP_MavlinkCommand home;
static AP_MavlinkCommand home;
/**
* Copy Constructor
*/
AP_MavlinkCommand(const AP_MavlinkCommand & v);
/**
* Copy Constructor
*/
AP_MavlinkCommand(const AP_MavlinkCommand & v);
/**
* Basic Constructor
* @param index Start at zero.
*/
AP_MavlinkCommand(uint16_t index, bool doLoad = true);
/**
* Basic Constructor
* @param index Start at zero.
*/
AP_MavlinkCommand(uint16_t index, bool doLoad = true);
/**
* Constructor for copying/ saving from a mavlink waypoint.
* @param cmd The mavlink_waopint_t structure for the command.
*/
AP_MavlinkCommand(const mavlink_waypoint_t & cmd);
/**
* Constructor for copying/ saving from a mavlink waypoint.
* @param cmd The mavlink_waopint_t structure for the command.
*/
AP_MavlinkCommand(const mavlink_waypoint_t & cmd);
bool save() {
return _data.save();
}
bool load() {
return _data.load();
}
uint8_t getSeq() const {
return _seq;
}
bool getAutocontinue() const {
return _data.get().autocontinue;
}
void setAutocontinue( bool val) {
_data.get().autocontinue = val;
}
void setSeq(uint8_t val) {
_seq = val;
}
MAV_CMD getCommand() const {
return _data.get().command;
}
void setCommand(MAV_CMD val) {
_data.get().command = val;
}
MAV_FRAME getFrame() const {
return _data.get().frame;
}
void setFrame(MAV_FRAME val) {
_data.get().frame = val;
}
float getParam1() const {
return _data.get().param1;
}
void setParam1(float val) {
_data.get().param1 = val;
}
float getParam2() const {
return _data.get().param2;
}
void setParam2(float val) {
_data.get().param2 = val;
}
float getParam3() const {
return _data.get().param3;
}
void setParam3(float val) {
_data.get().param3 = val;
}
float getParam4() const {
return _data.get().param4;
}
void setParam4(float val) {
_data.get().param4 = val;
}
float getX() const {
return _data.get().x;
}
void setX(float val) {
_data.get().x = val;
}
float getY() const {
return _data.get().y;
}
void setY(float val) {
_data.get().y = val;
}
float getZ() const {
return _data.get().z;
}
void setZ(float val) {
_data.get().z = val;
}
float getLatDeg() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
return getX();
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
void setLatDeg(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
setX(val);
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
break;
}
}
float getLonDeg() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
return getY();
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
void setLonDeg(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
setY(val);
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
break;
}
}
void setLon(float val) {
setLonDeg(val * rad2Deg);
}
void setLon_degInt(int32_t val) {
setLonDeg(val / 1.0e7);
}
void setLat_degInt(int32_t val) {
setLatDeg(val / 1.0e7);
}
int32_t getLon_degInt() const {
return getLonDeg() * 1e7;
}
int32_t getLat_degInt() const {
return getLatDeg() * 1e7;
}
float getLon() const {
return getLonDeg() * deg2Rad;
}
float getLat() const {
return getLatDeg() * deg2Rad;
}
void setLat(float val) {
setLatDeg(val * rad2Deg);
}
float getAlt() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
return getZ();
break;
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_LOCAL:
return -getZ() + home.getAlt();
break;
case MAV_FRAME_LOCAL_ENU:
return getZ() + home.getAlt();
break;
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
/**
* set the altitude in meters
*/
void setAlt(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
setZ(val);
break;
case MAV_FRAME_LOCAL:
setZ(home.getLonDeg() - val);
break;
case MAV_FRAME_LOCAL_ENU:
setZ(val - home.getLonDeg());
break;
case MAV_FRAME_MISSION:
default:
break;
}
}
/**
* Get the relative altitude to home
* @return relative altitude in meters
*/
float getRelAlt() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
return getZ() - home.getAlt();
break;
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_LOCAL:
return -getZ();
break;
case MAV_FRAME_LOCAL_ENU:
return getZ();
break;
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
/**
* set the relative altitude in meters from home (up)
*/
void setRelAlt(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
setZ(val + home.getAlt());
break;
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_LOCAL:
setZ(-val);
break;
case MAV_FRAME_LOCAL_ENU:
setZ(val);
break;
case MAV_FRAME_MISSION:
break;
}
}
bool save() {
return _data.save();
}
bool load() {
return _data.load();
}
uint8_t getSeq() const {
return _seq;
}
bool getAutocontinue() const {
return _data.get().autocontinue;
}
void setAutocontinue( bool val) {
_data.get().autocontinue = val;
}
void setSeq(uint8_t val) {
_seq = val;
}
MAV_CMD getCommand() const {
return _data.get().command;
}
void setCommand(MAV_CMD val) {
_data.get().command = val;
}
MAV_FRAME getFrame() const {
return _data.get().frame;
}
void setFrame(MAV_FRAME val) {
_data.get().frame = val;
}
float getParam1() const {
return _data.get().param1;
}
void setParam1(float val) {
_data.get().param1 = val;
}
float getParam2() const {
return _data.get().param2;
}
void setParam2(float val) {
_data.get().param2 = val;
}
float getParam3() const {
return _data.get().param3;
}
void setParam3(float val) {
_data.get().param3 = val;
}
float getParam4() const {
return _data.get().param4;
}
void setParam4(float val) {
_data.get().param4 = val;
}
float getX() const {
return _data.get().x;
}
void setX(float val) {
_data.get().x = val;
}
float getY() const {
return _data.get().y;
}
void setY(float val) {
_data.get().y = val;
}
float getZ() const {
return _data.get().z;
}
void setZ(float val) {
_data.get().z = val;
}
float getLatDeg() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
return getX();
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
void setLatDeg(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
setX(val);
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
break;
}
}
float getLonDeg() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
return getY();
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
void setLonDeg(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
setY(val);
break;
case MAV_FRAME_LOCAL:
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_MISSION:
default:
break;
}
}
void setLon(float val) {
setLonDeg(val * rad2Deg);
}
void setLon_degInt(int32_t val) {
setLonDeg(val / 1.0e7);
}
void setLat_degInt(int32_t val) {
setLatDeg(val / 1.0e7);
}
int32_t getLon_degInt() const {
return getLonDeg() * 1e7;
}
int32_t getLat_degInt() const {
return getLatDeg() * 1e7;
}
float getLon() const {
return getLonDeg() * deg2Rad;
}
float getLat() const {
return getLatDeg() * deg2Rad;
}
void setLat(float val) {
setLatDeg(val * rad2Deg);
}
float getAlt() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
return getZ();
break;
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_LOCAL:
return -getZ() + home.getAlt();
break;
case MAV_FRAME_LOCAL_ENU:
return getZ() + home.getAlt();
break;
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
/**
* set the altitude in meters
*/
void setAlt(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
setZ(val);
break;
case MAV_FRAME_LOCAL:
setZ(home.getLonDeg() - val);
break;
case MAV_FRAME_LOCAL_ENU:
setZ(val - home.getLonDeg());
break;
case MAV_FRAME_MISSION:
default:
break;
}
}
/**
* Get the relative altitude to home
* @return relative altitude in meters
*/
float getRelAlt() const {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
return getZ() - home.getAlt();
break;
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_LOCAL:
return -getZ();
break;
case MAV_FRAME_LOCAL_ENU:
return getZ();
break;
case MAV_FRAME_MISSION:
default:
return 0;
break;
}
}
/**
* set the relative altitude in meters from home (up)
*/
void setRelAlt(float val) {
switch (getFrame()) {
case MAV_FRAME_GLOBAL:
setZ(val + home.getAlt());
break;
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_LOCAL:
setZ(-val);
break;
case MAV_FRAME_LOCAL_ENU:
setZ(val);
break;
case MAV_FRAME_MISSION:
break;
}
}
float getRadius() const {
return getParam2();
}
float getRadius() const {
return getParam2();
}
void setRadius(float val) {
setParam2(val);
}
void setRadius(float val) {
setParam2(val);
}
/**
* conversion for outbound packets to ground station
* @return output the mavlink_waypoint_t packet
*/
mavlink_waypoint_t convert(uint8_t current) const;
/**
* conversion for outbound packets to ground station
* @return output the mavlink_waypoint_t packet
*/
mavlink_waypoint_t convert(uint8_t current) const;
/**
* Calculate the bearing from this command to the next command
* @param next The command to calculate the bearing to.
* @return the bearing
*/
float bearingTo(const AP_MavlinkCommand & next) const;
/**
* Calculate the bearing from this command to the next command
* @param next The command to calculate the bearing to.
* @return the bearing
*/
float bearingTo(const AP_MavlinkCommand & next) const;
/**
* Bearing form this command to a gps coordinate in integer units
* @param latDegInt latitude in degrees E-7
* @param lonDegInt longitude in degrees E-7
* @return
*/
float bearingTo(int32_t latDegInt, int32_t lonDegInt) const;
/**
* Bearing form this command to a gps coordinate in integer units
* @param latDegInt latitude in degrees E-7
* @param lonDegInt longitude in degrees E-7
* @return
*/
float bearingTo(int32_t latDegInt, int32_t lonDegInt) const;
/**
* Distance to another command
* @param next The command to measure to.
* @return The distance in meters.
*/
float distanceTo(const AP_MavlinkCommand & next) const;
/**
* Distance to another command
* @param next The command to measure to.
* @return The distance in meters.
*/
float distanceTo(const AP_MavlinkCommand & next) const;
/**
* Distance to a gps coordinate in integer units
* @param latDegInt latitude in degrees E-7
* @param lonDegInt longitude in degrees E-7
* @return The distance in meters.
*/
float distanceTo(int32_t lat_degInt, int32_t lon_degInt) const;
/**
* Distance to a gps coordinate in integer units
* @param latDegInt latitude in degrees E-7
* @param lonDegInt longitude in degrees E-7
* @return The distance in meters.
*/
float distanceTo(int32_t lat_degInt, int32_t lon_degInt) const;
float getPN(int32_t lat_degInt, int32_t lon_degInt) const {
// local tangent approximation at this waypoint
float deltaLat = (lat_degInt - getLat_degInt()) * degInt2Rad;
return deltaLat * rEarth;
}
float getPN(int32_t lat_degInt, int32_t lon_degInt) const {
// local tangent approximation at this waypoint
float deltaLat = (lat_degInt - getLat_degInt()) * degInt2Rad;
return deltaLat * rEarth;
}
float getPE(int32_t lat_degInt, int32_t lon_degInt) const {
// local tangent approximation at this waypoint
float deltaLon = (lon_degInt - getLon_degInt()) * degInt2Rad;
return cos(getLat()) * deltaLon * rEarth;
}
float getPE(int32_t lat_degInt, int32_t lon_degInt) const {
// local tangent approximation at this waypoint
float deltaLon = (lon_degInt - getLon_degInt()) * degInt2Rad;
return cos(getLat()) * deltaLon * rEarth;
}
float getPD(int32_t alt_intM) const {
return -(alt_intM / scale_m - getAlt());
}
float getPD(int32_t alt_intM) const {
return -(alt_intM / scale_m - getAlt());
}
float getLat(float pN) const {
float getLat(float pN) const {
return pN / rEarth + getLat();
}
return pN / rEarth + getLat();
}
float getLon(float pE) const {
float getLon(float pE) const {
return pE / rEarth / cos(getLat()) + getLon();
}
return pE / rEarth / cos(getLat()) + getLon();
}
/**
* Gets altitude in meters
* @param pD alt in meters
* @return
*/
float getAlt(float pD) const {
/**
* Gets altitude in meters
* @param pD alt in meters
* @return
*/
float getAlt(float pD) const {
return getAlt() - pD;
}
return getAlt() - pD;
}
//calculates cross track of a current location
float crossTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const;
//calculates cross track of a current location
float crossTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const;
// calculates along track distance of a current location
float alongTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const;
// calculates along track distance of a current location
float alongTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const;
};
} // namespace apo
#endif /* AP_MAVLINKCOMMAND_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -15,180 +15,194 @@
#include "AP_Var_keys.h"
#include "../AP_RangeFinder/AP_RangeFinder.h"
#include "../AP_IMU/AP_IMU.h"
#include "../APM_BMP085/APM_BMP085_hil.h"
#include "../APM_BMP085/APM_BMP085.h"
namespace apo {
AP_Navigator::AP_Navigator(AP_HardwareAbstractionLayer * hal) :
_hal(hal), _timeStamp(0), _roll(0), _rollRate(0), _pitch(0),
_pitchRate(0), _yaw(0), _yawRate(0), _airSpeed(0),
_groundSpeed(0), _vD(0), _lat_degInt(0),
_lon_degInt(0), _alt_intM(0) {
_hal(hal), _timeStamp(0), _roll(0), _rollRate(0), _pitch(0),
_pitchRate(0), _yaw(0), _yawRate(0), _airSpeed(0),
_groundSpeed(0), _vD(0), _lat_degInt(0),
_lon_degInt(0), _alt_intM(0) {
}
void AP_Navigator::calibrate() {
}
float AP_Navigator::getPD() const {
return AP_MavlinkCommand::home.getPD(getAlt_intM());
return AP_MavlinkCommand::home.getPD(getAlt_intM());
}
float AP_Navigator::getPE() const {
return AP_MavlinkCommand::home.getPE(getLat_degInt(), getLon_degInt());
return AP_MavlinkCommand::home.getPE(getLat_degInt(), getLon_degInt());
}
float AP_Navigator::getPN() const {
return AP_MavlinkCommand::home.getPN(getLat_degInt(), getLon_degInt());
return AP_MavlinkCommand::home.getPN(getLat_degInt(), getLon_degInt());
}
void AP_Navigator::setPD(float _pD) {
setAlt(AP_MavlinkCommand::home.getAlt(_pD));
setAlt(AP_MavlinkCommand::home.getAlt(_pD));
}
void AP_Navigator::setPE(float _pE) {
setLat(AP_MavlinkCommand::home.getLat(_pE));
setLat(AP_MavlinkCommand::home.getLat(_pE));
}
void AP_Navigator::setPN(float _pN) {
setLon(AP_MavlinkCommand::home.getLon(_pN));
setLon(AP_MavlinkCommand::home.getLon(_pN));
}
DcmNavigator::DcmNavigator(AP_HardwareAbstractionLayer * hal) :
AP_Navigator(hal), _dcm(), _imuOffsetAddress(0) {
AP_Navigator(hal), _dcm(), _imuOffsetAddress(0) {
// if orientation equal to front, store as front
/**
* rangeFinder<direction> is assigned values based on orientation which
* is specified in ArduPilotOne.pde.
*/
for (uint8_t i = 0; i < _hal-> rangeFinders.getSize(); i++) {
if (_hal->rangeFinders[i] == NULL)
continue;
if (_hal->rangeFinders[i]->orientation_x == 0
&& _hal->rangeFinders[i]->orientation_y == 0
&& _hal->rangeFinders[i]->orientation_z == 1)
_rangeFinderDown = _hal->rangeFinders[i];
}
// if orientation equal to front, store as front
/**
* rangeFinder<direction> is assigned values based on orientation which
* is specified in ArduPilotOne.pde.
*/
for (uint8_t i = 0; i < _hal-> rangeFinders.getSize(); i++) {
if (_hal->rangeFinders[i] == NULL)
continue;
if (_hal->rangeFinders[i]->orientation_x == 0
&& _hal->rangeFinders[i]->orientation_y == 0
&& _hal->rangeFinders[i]->orientation_z == 1)
_rangeFinderDown = _hal->rangeFinders[i];
}
if (_hal->getMode() == MODE_LIVE) {
if (_hal->adc)
_hal->imu = new AP_IMU_Oilpan(_hal->adc, k_sensorCalib);
if (_hal->imu)
_dcm = new AP_DCM(_hal->imu, _hal->gps, _hal->compass);
if (_hal->compass) {
_dcm->set_compass(_hal->compass);
if (_hal->getMode() == MODE_LIVE) {
}
}
if (_hal->adc) {
_hal->imu = new AP_IMU_Oilpan(_hal->adc, k_sensorCalib);
}
if (_hal->imu) {
_dcm = new AP_DCM(_hal->imu, _hal->gps, _hal->compass);
// tune down dcm
_dcm->kp_roll_pitch(0.030000);
_dcm->ki_roll_pitch(0.00001278), // 50 hz I term
// tune down compass in dcm
_dcm->kp_yaw(0.08);
_dcm->ki_yaw(0);
}
if (_hal->compass) {
_dcm->set_compass(_hal->compass);
}
}
}
void DcmNavigator::calibrate() {
AP_Navigator::calibrate();
AP_Navigator::calibrate();
// TODO: handle cold/warm restart
if (_hal->imu) {
_hal->imu->init(IMU::COLD_START,delay);
}
// TODO: handle cold/warm restart
if (_hal->imu) {
_hal->imu->init(IMU::COLD_START,delay);
}
}
void DcmNavigator::updateFast(float dt) {
if (_hal->getMode() != MODE_LIVE)
return;
if (_hal->getMode() != MODE_LIVE)
return;
setTimeStamp(micros()); // if running in live mode, record new time stamp
setTimeStamp(micros()); // if running in live mode, record new time stamp
//_hal->debug->println_P(PSTR("nav loop"));
//_hal->debug->println_P(PSTR("nav loop"));
/**
* The altitued is read off the barometer by implementing the following formula:
* altitude (in m) = 44330*(1-(p/po)^(1/5.255)),
* where, po is pressure in Pa at sea level (101325 Pa).
* See http://www.sparkfun.com/tutorials/253 or type this formula
* in a search engine for more information.
* altInt contains the altitude in meters.
*/
if (_hal->baro) {
/**
* The altitued is read off the barometer by implementing the following formula:
* altitude (in m) = 44330*(1-(p/po)^(1/5.255)),
* where, po is pressure in Pa at sea level (101325 Pa).
* See http://www.sparkfun.com/tutorials/253 or type this formula
* in a search engine for more information.
* altInt contains the altitude in meters.
*/
if (_hal->baro) {
if (_rangeFinderDown != NULL && _rangeFinderDown->distance <= 695)
setAlt(_rangeFinderDown->distance);
if (_rangeFinderDown != NULL && _rangeFinderDown->distance <= 695)
setAlt(_rangeFinderDown->distance);
else {
float tmp = (_hal->baro->Press / 101325.0);
tmp = pow(tmp, 0.190295);
//setAlt(44330 * (1.0 - tmp)); //sets the altitude in meters XXX wrong, baro reads 0 press
setAlt(0.0);
}
}
else {
float tmp = (_hal->baro->Press / 101325.0);
tmp = pow(tmp, 0.190295);
//setAlt(44330 * (1.0 - tmp)); //sets the altitude in meters XXX wrong, baro reads 0 press
setAlt(0.0);
}
}
// dcm class for attitude
if (_dcm) {
_dcm->update_DCM_fast();
setRoll(_dcm->roll);
setPitch(_dcm->pitch);
setYaw(_dcm->yaw);
setRollRate(_dcm->get_gyro().x);
setPitchRate(_dcm->get_gyro().y);
setYawRate(_dcm->get_gyro().z);
// dcm class for attitude
if (_dcm) {
_dcm->update_DCM_fast();
setRoll(_dcm->roll);
setPitch(_dcm->pitch);
setYaw(_dcm->yaw);
setRollRate(_dcm->get_gyro().x);
setPitchRate(_dcm->get_gyro().y);
setYawRate(_dcm->get_gyro().z);
/*
* accel/gyro debug
*/
/*
Vector3f accel = _hal->imu->get_accel();
Vector3f gyro = _hal->imu->get_gyro();
Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"),
accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z);
*/
}
/*
* accel/gyro debug
*/
/*
Vector3f accel = _hal->imu->get_accel();
Vector3f gyro = _hal->imu->get_gyro();
Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"),
accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z);
*/
}
}
void DcmNavigator::updateSlow(float dt) {
if (_hal->getMode() != MODE_LIVE)
return;
if (_hal->getMode() != MODE_LIVE)
return;
setTimeStamp(micros()); // if running in live mode, record new time stamp
setTimeStamp(micros()); // if running in live mode, record new time stamp
if (_hal->gps) {
_hal->gps->update();
updateGpsLight();
if (_hal->gps->fix && _hal->gps->new_data) {
setLat_degInt(_hal->gps->latitude);
setLon_degInt(_hal->gps->longitude);
setAlt_intM(_hal->gps->altitude * 10); // gps in cm, intM in mm
setGroundSpeed(_hal->gps->ground_speed / 100.0); // gps is in cm/s
}
}
if (_hal->gps) {
_hal->gps->update();
updateGpsLight();
if (_hal->gps->fix && _hal->gps->new_data) {
setLat_degInt(_hal->gps->latitude);
setLon_degInt(_hal->gps->longitude);
setAlt_intM(_hal->gps->altitude * 10); // gps in cm, intM in mm
setGroundSpeed(_hal->gps->ground_speed / 100.0); // gps is in cm/s
}
}
if (_hal->compass) {
_hal->compass->read();
_hal->compass->calculate(_dcm->get_dcm_matrix());
_hal->compass->null_offsets(_dcm->get_dcm_matrix());
//_hal->debug->printf_P(PSTR("heading: %f"), _hal->compass->heading);
}
if (_hal->compass) {
_hal->compass->read();
_hal->compass->calculate(_dcm->get_dcm_matrix());
_hal->compass->null_offsets(_dcm->get_dcm_matrix());
//_hal->debug->printf_P(PSTR("heading: %f"), _hal->compass->heading);
}
}
void DcmNavigator::updateGpsLight(void) {
// GPS LED on if we have a fix or Blink GPS LED if we are receiving data
// ---------------------------------------------------------------------
static bool GPS_light = false;
switch (_hal->gps->status()) {
case (2):
//digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix.
break;
// GPS LED on if we have a fix or Blink GPS LED if we are receiving data
// ---------------------------------------------------------------------
static bool GPS_light = false;
switch (_hal->gps->status()) {
case (2):
//digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix.
break;
case (1):
if (_hal->gps->valid_read == true) {
GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock
if (GPS_light) {
digitalWrite(_hal->cLedPin, LOW);
} else {
digitalWrite(_hal->cLedPin, HIGH);
}
_hal->gps->valid_read = false;
}
break;
case (1):
if (_hal->gps->valid_read == true) {
GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock
if (GPS_light) {
digitalWrite(_hal->cLedPin, LOW);
} else {
digitalWrite(_hal->cLedPin, HIGH);
}
_hal->gps->valid_read = false;
}
break;
default:
digitalWrite(_hal->cLedPin, LOW);
break;
}
default:
digitalWrite(_hal->cLedPin, LOW);
break;
}
}
} // namespace apo
// vim:ts=4:sw=4:expandtab

View File

@ -33,195 +33,195 @@ class AP_HardwareAbstractionLayer;
/// Navigator class
class AP_Navigator {
public:
AP_Navigator(AP_HardwareAbstractionLayer * hal);
virtual void calibrate();
virtual void updateFast(float dt) = 0;
virtual void updateSlow(float dt) = 0;
float getPD() const;
float getPE() const;
float getPN() const;
void setPD(float _pD);
void setPE(float _pE);
void setPN(float _pN);
AP_Navigator(AP_HardwareAbstractionLayer * hal);
virtual void calibrate();
virtual void updateFast(float dt) = 0;
virtual void updateSlow(float dt) = 0;
float getPD() const;
float getPE() const;
float getPN() const;
void setPD(float _pD);
void setPE(float _pE);
void setPN(float _pN);
float getAirSpeed() const {
return _airSpeed;
}
float getAirSpeed() const {
return _airSpeed;
}
int32_t getAlt_intM() const {
return _alt_intM;
}
int32_t getAlt_intM() const {
return _alt_intM;
}
float getAlt() const {
return _alt_intM / scale_m;
}
float getAlt() const {
return _alt_intM / scale_m;
}
void setAlt(float _alt) {
this->_alt_intM = _alt * scale_m;
}
void setAlt(float _alt) {
this->_alt_intM = _alt * scale_m;
}
float getLat() const {
//Serial.print("getLatfirst");
//Serial.println(_lat_degInt * degInt2Rad);
return _lat_degInt * degInt2Rad;
}
float getLat() const {
//Serial.print("getLatfirst");
//Serial.println(_lat_degInt * degInt2Rad);
return _lat_degInt * degInt2Rad;
}
void setLat(float _lat) {
//Serial.print("setLatfirst");
//Serial.println(_lat * rad2DegInt);
setLat_degInt(_lat*rad2DegInt);
}
void setLat(float _lat) {
//Serial.print("setLatfirst");
//Serial.println(_lat * rad2DegInt);
setLat_degInt(_lat*rad2DegInt);
}
float getLon() const {
return _lon_degInt * degInt2Rad;
}
float getLon() const {
return _lon_degInt * degInt2Rad;
}
void setLon(float _lon) {
this->_lon_degInt = _lon * rad2DegInt;
}
void setLon(float _lon) {
this->_lon_degInt = _lon * rad2DegInt;
}
float getVD() const {
return _vD;
}
float getVD() const {
return _vD;
}
float getVE() const {
return sin(getYaw()) * getGroundSpeed();
}
float getVE() const {
return sin(getYaw()) * getGroundSpeed();
}
float getGroundSpeed() const {
return _groundSpeed;
}
float getGroundSpeed() const {
return _groundSpeed;
}
int32_t getLat_degInt() const {
//Serial.print("getLat_degInt");
//Serial.println(_lat_degInt);
return _lat_degInt;
int32_t getLat_degInt() const {
//Serial.print("getLat_degInt");
//Serial.println(_lat_degInt);
return _lat_degInt;
}
}
int32_t getLon_degInt() const {
return _lon_degInt;
}
int32_t getLon_degInt() const {
return _lon_degInt;
}
float getVN() const {
return cos(getYaw()) * getGroundSpeed();
}
float getVN() const {
return cos(getYaw()) * getGroundSpeed();
}
float getPitch() const {
return _pitch;
}
float getPitch() const {
return _pitch;
}
float getPitchRate() const {
return _pitchRate;
}
float getPitchRate() const {
return _pitchRate;
}
float getRoll() const {
return _roll;
}
float getRoll() const {
return _roll;
}
float getRollRate() const {
return _rollRate;
}
float getRollRate() const {
return _rollRate;
}
float getYaw() const {
return _yaw;
}
float getYaw() const {
return _yaw;
}
float getYawRate() const {
return _yawRate;
}
float getYawRate() const {
return _yawRate;
}
void setAirSpeed(float airSpeed) {
_airSpeed = airSpeed;
}
void setAirSpeed(float airSpeed) {
_airSpeed = airSpeed;
}
void setAlt_intM(int32_t alt_intM) {
_alt_intM = alt_intM;
}
void setAlt_intM(int32_t alt_intM) {
_alt_intM = alt_intM;
}
void setVD(float vD) {
_vD = vD;
}
void setVD(float vD) {
_vD = vD;
}
void setGroundSpeed(float groundSpeed) {
_groundSpeed = groundSpeed;
}
void setGroundSpeed(float groundSpeed) {
_groundSpeed = groundSpeed;
}
void setLat_degInt(int32_t lat_degInt) {
_lat_degInt = lat_degInt;
//Serial.print("setLat_degInt");
//Serial.println(_lat_degInt);
}
void setLat_degInt(int32_t lat_degInt) {
_lat_degInt = lat_degInt;
//Serial.print("setLat_degInt");
//Serial.println(_lat_degInt);
}
void setLon_degInt(int32_t lon_degInt) {
_lon_degInt = lon_degInt;
}
void setLon_degInt(int32_t lon_degInt) {
_lon_degInt = lon_degInt;
}
void setPitch(float pitch) {
_pitch = pitch;
}
void setPitch(float pitch) {
_pitch = pitch;
}
void setPitchRate(float pitchRate) {
_pitchRate = pitchRate;
}
void setPitchRate(float pitchRate) {
_pitchRate = pitchRate;
}
void setRoll(float roll) {
_roll = roll;
}
void setRoll(float roll) {
_roll = roll;
}
void setRollRate(float rollRate) {
_rollRate = rollRate;
}
void setRollRate(float rollRate) {
_rollRate = rollRate;
}
void setYaw(float yaw) {
_yaw = yaw;
}
void setYaw(float yaw) {
_yaw = yaw;
}
void setYawRate(float yawRate) {
_yawRate = yawRate;
}
void setTimeStamp(int32_t timeStamp) {
_timeStamp = timeStamp;
}
int32_t getTimeStamp() const {
return _timeStamp;
}
void setYawRate(float yawRate) {
_yawRate = yawRate;
}
void setTimeStamp(int32_t timeStamp) {
_timeStamp = timeStamp;
}
int32_t getTimeStamp() const {
return _timeStamp;
}
protected:
AP_HardwareAbstractionLayer * _hal;
AP_HardwareAbstractionLayer * _hal;
private:
int32_t _timeStamp; // micros clock
float _roll; // rad
float _rollRate; //rad/s
float _pitch; // rad
float _pitchRate; // rad/s
float _yaw; // rad
float _yawRate; // rad/s
float _airSpeed; // m/s
float _groundSpeed; // m/s
float _vD; // m/s
int32_t _lat_degInt; // deg / 1e7
int32_t _lon_degInt; // deg / 1e7
int32_t _alt_intM; // meters / 1e3
int32_t _timeStamp; // micros clock
float _roll; // rad
float _rollRate; //rad/s
float _pitch; // rad
float _pitchRate; // rad/s
float _yaw; // rad
float _yawRate; // rad/s
float _airSpeed; // m/s
float _groundSpeed; // m/s
float _vD; // m/s
int32_t _lat_degInt; // deg / 1e7
int32_t _lon_degInt; // deg / 1e7
int32_t _alt_intM; // meters / 1e3
};
class DcmNavigator: public AP_Navigator {
private:
/**
* Sensors
*/
/**
* Sensors
*/
RangeFinder * _rangeFinderDown;
AP_DCM * _dcm;
IMU * _imu;
uint16_t _imuOffsetAddress;
RangeFinder * _rangeFinderDown;
AP_DCM * _dcm;
IMU * _imu;
uint16_t _imuOffsetAddress;
public:
DcmNavigator(AP_HardwareAbstractionLayer * hal);
virtual void calibrate();
virtual void updateFast(float dt);
virtual void updateSlow(float dt);
void updateGpsLight(void);
DcmNavigator(AP_HardwareAbstractionLayer * hal);
virtual void calibrate();
virtual void updateFast(float dt);
virtual void updateSlow(float dt);
void updateGpsLight(void);
};
} // namespace apo

View File

@ -18,85 +18,86 @@
namespace apo {
AP_RcChannel::AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name,
APM_RC_Class & rc, const uint8_t & ch, const uint16_t & pwmMin,
const uint16_t & pwmNeutral, const uint16_t & pwmMax,
const rcMode_t & rcMode, const bool & reverse, const float & scale) :
AP_Var_group(keyValue, name), _ch(this, 1, ch, PSTR("ch")),
_pwmMin(this, 2, pwmMin, PSTR("pMin")),
_pwmNeutral(this, 3, pwmNeutral, PSTR("pNtrl")),
_pwmMax(this, 4, pwmMax, PSTR("pMax")),
_reverse(this, 5, reverse, PSTR("rev")),
_scale(scale == 0 ? AP_Float(0) : AP_Float(this,6,reverse,PSTR("scale"))),
_rcMode(rcMode), _rc(rc), _pwm(pwmNeutral) {
//Serial.print("pwm after ctor: "); Serial.println(pwmNeutral);
if (rcMode == RC_MODE_IN)
return;
//Serial.print("pwm set for ch: "); Serial.println(int(ch));
rc.OutputCh(ch, pwmNeutral);
APM_RC_Class & rc, const uint8_t & ch, const uint16_t & pwmMin,
const uint16_t & pwmNeutral, const uint16_t & pwmMax,
const rcMode_t & rcMode, const bool & reverse, const float & scale) :
AP_Var_group(keyValue, name), _ch(this, 1, ch, PSTR("ch")),
_pwmMin(this, 2, pwmMin, PSTR("pMin")),
_pwmNeutral(this, 3, pwmNeutral, PSTR("pNtrl")),
_pwmMax(this, 4, pwmMax, PSTR("pMax")),
_reverse(this, 5, reverse, PSTR("rev")),
_scale(scale == 0 ? AP_Float(0) : AP_Float(this,6,reverse,PSTR("scale"))),
_rcMode(rcMode), _rc(rc), _pwm(pwmNeutral) {
//Serial.print("pwm after ctor: "); Serial.println(pwmNeutral);
if (rcMode == RC_MODE_IN)
return;
//Serial.print("pwm set for ch: "); Serial.println(int(ch));
rc.OutputCh(ch, pwmNeutral);
}
uint16_t AP_RcChannel::getRadioPwm() {
if (_rcMode == RC_MODE_OUT) {
Serial.print("tryng to read from output channel: ");
Serial.println(int(_ch));
return _pwmNeutral; // if this happens give a safe value of neutral
}
return _rc.InputCh(_ch);
if (_rcMode == RC_MODE_OUT) {
Serial.print("tryng to read from output channel: ");
Serial.println(int(_ch));
return _pwmNeutral; // if this happens give a safe value of neutral
}
return _rc.InputCh(_ch);
}
void AP_RcChannel::setPwm(uint16_t pwm) {
//Serial.printf("pwm in setPwm: %d\n", pwm);
//Serial.printf("reverse: %s\n", (reverse)?"true":"false");
//Serial.printf("pwm in setPwm: %d\n", pwm);
//Serial.printf("reverse: %s\n", (reverse)?"true":"false");
// apply reverse
if (_reverse)
pwm = int16_t(_pwmNeutral - pwm) + _pwmNeutral;
//Serial.printf("pwm after reverse: %d\n", pwm);
// apply reverse
if (_reverse)
pwm = int16_t(_pwmNeutral - pwm) + _pwmNeutral;
//Serial.printf("pwm after reverse: %d\n", pwm);
// apply saturation
if (_pwm > uint8_t(_pwmMax))
_pwm = _pwmMax;
if (_pwm < uint8_t(_pwmMin))
_pwm = _pwmMin;
_pwm = pwm;
// apply saturation
if (_pwm > uint8_t(_pwmMax))
_pwm = _pwmMax;
if (_pwm < uint8_t(_pwmMin))
_pwm = _pwmMin;
_pwm = pwm;
//Serial.print("ch: "); Serial.print(ch); Serial.print(" pwm: "); Serial.println(pwm);
if (_rcMode == RC_MODE_IN)
return;
_rc.OutputCh(_ch, _pwm);
//Serial.print("ch: "); Serial.print(ch); Serial.print(" pwm: "); Serial.println(pwm);
if (_rcMode == RC_MODE_IN)
return;
_rc.OutputCh(_ch, _pwm);
}
uint16_t AP_RcChannel::_positionToPwm(const float & position) {
uint16_t pwm;
//Serial.printf("position: %f\n", position);
if (position < 0)
pwm = position * int16_t(_pwmNeutral - _pwmMin) + _pwmNeutral;
else
pwm = position * int16_t(_pwmMax - _pwmNeutral) + _pwmNeutral;
uint16_t pwm;
//Serial.printf("position: %f\n", position);
if (position < 0)
pwm = position * int16_t(_pwmNeutral - _pwmMin) + _pwmNeutral;
else
pwm = position * int16_t(_pwmMax - _pwmNeutral) + _pwmNeutral;
if (pwm > uint16_t(_pwmMax))
pwm = _pwmMax;
if (pwm < uint16_t(_pwmMin))
pwm = _pwmMin;
return pwm;
if (pwm > uint16_t(_pwmMax))
pwm = _pwmMax;
if (pwm < uint16_t(_pwmMin))
pwm = _pwmMin;
return pwm;
}
float AP_RcChannel::_pwmToPosition(const uint16_t & pwm) {
float position;
// note a piece-wise linear mapping occurs if the pwm ranges
// are not symmetric about pwmNeutral
if (pwm < uint8_t(_pwmNeutral))
position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t(
_pwmNeutral - _pwmMin);
else
position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t(
_pwmMax - _pwmNeutral);
if (position > 1)
position = 1;
if (position < -1)
position = -1;
return position;
float position;
// note a piece-wise linear mapping occurs if the pwm ranges
// are not symmetric about pwmNeutral
if (pwm < uint8_t(_pwmNeutral))
position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t(
_pwmNeutral - _pwmMin);
else
position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t(
_pwmMax - _pwmNeutral);
if (position > 1)
position = 1;
if (position < -1)
position = -1;
return position;
}
} // namespace apo
// vim:ts=4:sw=4:expandtab

View File

@ -14,7 +14,7 @@
namespace apo {
enum rcMode_t {
RC_MODE_IN, RC_MODE_OUT, RC_MODE_INOUT
RC_MODE_IN, RC_MODE_OUT, RC_MODE_INOUT
};
/// @class AP_RcChannel
@ -23,62 +23,63 @@ class AP_RcChannel: public AP_Var_group {
public:
/// Constructor
AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, APM_RC_Class & rc,
const uint8_t & ch, const uint16_t & pwmMin,
const uint16_t & pwmNeutral, const uint16_t & pwmMax,
const rcMode_t & rcMode,
const bool & reverse, const float & scale = 0);
/// Constructor
AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, APM_RC_Class & rc,
const uint8_t & ch, const uint16_t & pwmMin,
const uint16_t & pwmNeutral, const uint16_t & pwmMax,
const rcMode_t & rcMode,
const bool & reverse, const float & scale = 0);
// configuration
AP_Uint8 _ch;
AP_Uint16 _pwmMin;
AP_Uint16 _pwmNeutral;
AP_Uint16 _pwmMax;
rcMode_t _rcMode;
AP_Bool _reverse;
AP_Float _scale;
// configuration
AP_Uint8 _ch;
AP_Uint16 _pwmMin;
AP_Uint16 _pwmNeutral;
AP_Uint16 _pwmMax;
rcMode_t _rcMode;
AP_Bool _reverse;
AP_Float _scale;
// get
uint16_t getPwm() {
return _pwm;
}
uint16_t getRadioPwm();
float getPosition() {
return _pwmToPosition(getPwm());
}
float getRadioPosition() {
return _pwmToPosition(getRadioPwm());
}
float getScaled() {
return _scale*getPwm();
}
// get
uint16_t getPwm() {
return _pwm;
}
uint16_t getRadioPwm();
float getPosition() {
return _pwmToPosition(getPwm());
}
float getRadioPosition() {
return _pwmToPosition(getRadioPwm());
}
float getScaled() {
return _scale*getPwm();
}
// set
void setUsingRadio() {
if (_rcMode != RC_MODE_OUT) setPwm(getRadioPwm());
}
void setPwm(uint16_t pwm);
void setPosition(float position) {
setPwm(_positionToPwm(position));
}
void setScaled(float val) {
setPwm(val/_scale);
}
// set
void setUsingRadio() {
if (_rcMode != RC_MODE_OUT) setPwm(getRadioPwm());
}
void setPwm(uint16_t pwm);
void setPosition(float position) {
setPwm(_positionToPwm(position));
}
void setScaled(float val) {
setPwm(val/_scale);
}
protected:
// configuration
APM_RC_Class & _rc;
// configuration
APM_RC_Class & _rc;
// internal states
uint16_t _pwm; // this is the internal state, position is just created when needed
// internal states
uint16_t _pwm; // this is the internal state, position is just created when needed
// private methods
uint16_t _positionToPwm(const float & position);
float _pwmToPosition(const uint16_t & pwm);
// private methods
uint16_t _positionToPwm(const float & position);
float _pwmToPosition(const uint16_t & pwm);
};
} // apo
#endif // AP_RCCHANNEL_H
// vim:ts=4:sw=4:expandtab

View File

@ -3,22 +3,23 @@
enum keys {
// general
k_config = 0,
k_cntrl,
k_guide,
k_sensorCalib,
// general
k_config = 0,
k_cntrl,
k_guide,
k_sensorCalib,
k_radioChannelsStart=10,
k_radioChannelsStart=10,
k_controllersStart=30,
k_controllersStart=30,
k_customStart=100,
k_customStart=100,
// 200-256 reserved for commands
k_commands = 200
// 200-256 reserved for commands
k_commands = 200
};
// max 256 keys
#endif
// vim:ts=4:sw=4:expandtab

View File

@ -21,3 +21,4 @@ const float degInt2Rad = deg2Rad / scale_deg; // degrees x 1e7 to radians
#define MAV_MODE_FAILSAFE MAV_MODE_TEST3
#endif /* CONSTANTS_H_ */
// vim:ts=4:sw=4:expandtab

View File

@ -1,7 +1,7 @@
/*
AnalogReadSerial
Reads an analog input on pin 0, prints the result to the serial monitor
Reads an analog input on pin 0, prints the result to the serial monitor
This example code is in the public domain.
*/
@ -10,40 +10,40 @@
int packetDrops = 0;
void handleMessage(mavlink_message_t * msg) {
Serial.print(", received mavlink message: ");
Serial.print(msg->msgid, DEC);
Serial.print(", received mavlink message: ");
Serial.print(msg->msgid, DEC);
}
void setup() {
Serial.begin(57600);
Serial3.begin(57600);
mavlink_comm_0_port = &Serial3;
packetDrops = 0;
Serial.begin(57600);
Serial3.begin(57600);
mavlink_comm_0_port = &Serial3;
packetDrops = 0;
}
void loop() {
mavlink_msg_heartbeat_send(MAVLINK_COMM_0, mavlink_system.type,
MAV_AUTOPILOT_ARDUPILOTMEGA);
Serial.print("heartbeat sent");
mavlink_msg_heartbeat_send(MAVLINK_COMM_0, mavlink_system.type,
MAV_AUTOPILOT_ARDUPILOTMEGA);
Serial.print("heartbeat sent");
// receive new packets
mavlink_message_t msg;
mavlink_status_t status;
// receive new packets
mavlink_message_t msg;
mavlink_status_t status;
Serial.print(", bytes available: ");
Serial.print(comm_get_available(MAVLINK_COMM_0));
while (comm_get_available( MAVLINK_COMM_0)) {
uint8_t c = comm_receive_ch(MAVLINK_COMM_0);
Serial.print(", bytes available: ");
Serial.print(comm_get_available(MAVLINK_COMM_0));
while (comm_get_available( MAVLINK_COMM_0)) {
uint8_t c = comm_receive_ch(MAVLINK_COMM_0);
// Try to get a new message
if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status))
handleMessage(&msg);
}
// Try to get a new message
if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status))
handleMessage(&msg);
}
// Update packet drops counter
packetDrops += status.packet_rx_drop_count;
// Update packet drops counter
packetDrops += status.packet_rx_drop_count;
Serial.print(", dropped packets: ");
Serial.println(packetDrops);
delay(1000);
Serial.print(", dropped packets: ");
Serial.println(packetDrops);
delay(1000);
}

View File

@ -19,91 +19,91 @@ using namespace apo;
class RadioTest {
private:
float testPosition;
int8_t testSign;
enum {
version,
rollKey,
pitchKey,
thrKey,
yawKey,
ch5Key,
ch6Key,
ch7Key,
ch8Key
};
Vector<AP_RcChannel *> ch;
float testPosition;
int8_t testSign;
enum {
version,
rollKey,
pitchKey,
thrKey,
yawKey,
ch5Key,
ch6Key,
ch7Key,
ch8Key
};
Vector<AP_RcChannel *> ch;
public:
RadioTest() :
testPosition(2), testSign(1) {
ch.push_back(
new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100,
1500, 1900));
ch.push_back(
new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
1900));
RadioTest() :
testPosition(2), testSign(1) {
ch.push_back(
new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500,
1900, RC_MODE_INOUT, false));
ch.push_back(
new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100,
1500, 1900, RC_MODE_INOUT, false));
ch.push_back(
new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500,
1900, RC_MODE_INOUT, false));
ch.push_back(
new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500,
1900, RC_MODE_INOUT, false));
ch.push_back(
new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500,
1900, RC_MODE_INOUT, false));
ch.push_back(
new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500,
1900, RC_MODE_INOUT, false));
ch.push_back(
new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500,
1900, RC_MODE_INOUT, false));
ch.push_back(
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
1900, RC_MODE_INOUT, false));
Serial.begin(115200);
delay(2000);
Serial.println("ArduPilot RC Channel test");
APM_RC.Init(); // APM Radio initialization
delay(2000);
}
Serial.begin(115200);
delay(2000);
Serial.println("ArduPilot RC Channel test");
APM_RC.Init(); // APM Radio initialization
delay(2000);
}
void update() {
// read the radio
for (uint8_t i = 0; i < ch.getSize(); i++)
ch[i]->setUsingRadio();
void update() {
// read the radio
for (uint8_t i = 0; i < ch.getSize(); i++)
ch[i]->setUsingRadio();
// print channel names
Serial.print("\t\t");
static char name[7];
for (uint8_t i = 0; i < ch.getSize(); i++) {
ch[i]->copy_name(name, 7);
Serial.printf("%7s\t", name);
}
Serial.println();
// print channel names
Serial.print("\t\t");
static char name[7];
for (uint8_t i = 0; i < ch.getSize(); i++) {
ch[i]->copy_name(name, 7);
Serial.printf("%7s\t", name);
}
Serial.println();
// print pwm
Serial.printf("pwm :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7d\t", ch[i]->getPwm());
Serial.println();
// print pwm
Serial.printf("pwm :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7d\t", ch[i]->getPwm());
Serial.println();
// print position
Serial.printf("position :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7.2f\t", ch[i]->getPosition());
Serial.println();
// print position
Serial.printf("position :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7.2f\t", ch[i]->getPosition());
Serial.println();
delay(500);
}
delay(500);
}
};
RadioTest * test;
void setup() {
test = new RadioTest;
test = new RadioTest;
}
void loop() {
test->update();
test->update();
}

View File

@ -19,107 +19,107 @@ using namespace apo;
class RadioTest {
private:
float testPosition;
int8_t testSign;
enum {
version,
rollKey,
pitchKey,
thrKey,
yawKey,
ch5Key,
ch6Key,
ch7Key,
ch8Key
};
Vector<AP_RcChannel *> ch;
float testPosition;
int8_t testSign;
enum {
version,
rollKey,
pitchKey,
thrKey,
yawKey,
ch5Key,
ch6Key,
ch7Key,
ch8Key
};
Vector<AP_RcChannel *> ch;
public:
RadioTest() :
testPosition(2), testSign(1) {
ch.push_back(
new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100,
1500, 1900));
ch.push_back(
new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500,
1900));
ch.push_back(
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
1900));
RadioTest() :
testPosition(2), testSign(1) {
ch.push_back(
new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500,
1900,RC_MODE_INOUT,false));
ch.push_back(
new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100,
1500, 1900,RC_MODE_INOUT,false));
ch.push_back(
new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500,
1900,RC_MODE_INOUT,false));
ch.push_back(
new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500,
1900,RC_MODE_INOUT,false));
ch.push_back(
new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500,
1900,RC_MODE_INOUT,false));
ch.push_back(
new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500,
1900,RC_MODE_INOUT,false));
ch.push_back(
new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500,
1900,RC_MODE_INOUT,false));
ch.push_back(
new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500,
1900,RC_MODE_INOUT,false));
Serial.begin(115200);
delay(2000);
Serial.println("ArduPilot RC Channel test");
APM_RC.Init(); // APM Radio initialization
delay(2000);
}
Serial.begin(115200);
delay(2000);
Serial.println("ArduPilot RC Channel test");
APM_RC.Init(); // APM Radio initialization
delay(2000);
}
void update() {
// update test value
testPosition += testSign * .1;
if (testPosition > 1) {
//eepromRegistry.print(Serial); // show eeprom map
testPosition = 1;
testSign = -1;
} else if (testPosition < -1) {
testPosition = -1;
testSign = 1;
}
void update() {
// update test value
testPosition += testSign * .1;
if (testPosition > 1) {
//eepromRegistry.print(Serial); // show eeprom map
testPosition = 1;
testSign = -1;
} else if (testPosition < -1) {
testPosition = -1;
testSign = 1;
}
// set channel positions
for (uint8_t i = 0; i < ch.getSize(); i++)
ch[i]->setPosition(testPosition);
// set channel positions
for (uint8_t i = 0; i < ch.getSize(); i++)
ch[i]->setPosition(testPosition);
// print test position
Serial.printf("\nnormalized position (%f)\n", testPosition);
// print test position
Serial.printf("\nnormalized position (%f)\n", testPosition);
// print channel names
Serial.print("\t\t");
static char name[7];
for (uint8_t i = 0; i < ch.getSize(); i++) {
ch[i]->copy_name(name, 7);
Serial.printf("%7s\t", name);
}
Serial.println();
// print channel names
Serial.print("\t\t");
static char name[7];
for (uint8_t i = 0; i < ch.getSize(); i++) {
ch[i]->copy_name(name, 7);
Serial.printf("%7s\t", name);
}
Serial.println();
// print pwm
Serial.printf("pwm :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7d\t", ch[i]->getRadioPwm());
Serial.println();
// print pwm
Serial.printf("pwm :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7d\t", ch[i]->getRadioPwm());
Serial.println();
// print position
Serial.printf("position :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7.2f\t", ch[i]->getRadioPosition());
Serial.println();
// print position
Serial.printf("position :\t");
for (uint8_t i = 0; i < ch.getSize(); i++)
Serial.printf("%7.2f\t", ch[i]->getRadioPosition());
Serial.println();
delay(500);
}
delay(500);
}
};
RadioTest * test;
void setup() {
test = new RadioTest;
test = new RadioTest;
}
void loop() {
test->update();
test->update();
}
// vim:ts=4:sw=4:expandtab

View File

@ -171,7 +171,7 @@ else
endif
# these are library objects we don't want in the desktop build (maybe we'll add them later)
NODESKTOP := FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp RC_Channel/RC_Channel_aux.cpp
NODESKTOP := FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp
#
# Find sketchbook libraries referenced by the sketch.

View File

@ -25,3 +25,6 @@ heli:
helihil:
make -f $(DESKTOP)/Makefile.desktop EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME -DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
mavlink10:
make -f $(DESKTOP)/Makefile.desktop EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DMAVLINK10 -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"

View File

@ -11,7 +11,11 @@ BetterStream *mavlink_comm_1_port;
// this might need to move to the flight software
mavlink_system_t mavlink_system = {7,1,0,0};
#include "include/mavlink_helpers.h"
#ifdef MAVLINK10
# include "include_v1.0/mavlink_helpers.h"
#else
# include "include/mavlink_helpers.h"
#endif
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
{

View File

@ -10,13 +10,21 @@
#define MAVLINK_SEPARATE_HELPERS
#include "include/ardupilotmega/version.h"
#ifdef MAVLINK10
# include "include_v1.0/ardupilotmega/version.h"
#else
# include "include/ardupilotmega/version.h"
#endif
// this allows us to make mavlink_message_t much smaller
#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
#define MAVLINK_COMM_NUM_BUFFERS 2
#include "include/mavlink_types.h"
#ifdef MAVLINK10
# include "include_v1.0/mavlink_types.h"
#else
# include "include/mavlink_types.h"
#endif
/// MAVLink stream used for HIL interaction
extern BetterStream *mavlink_comm_0_port;
@ -109,7 +117,11 @@ static inline int comm_get_txspace(mavlink_channel_t chan)
}
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#include "include/ardupilotmega/mavlink.h"
#ifdef MAVLINK10
# include "include_v1.0/ardupilotmega/mavlink.h"
#else
# include "include/ardupilotmega/mavlink.h"
#endif
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid);

View File

@ -12,15 +12,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
#endif
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
#endif
#include "../protocol.h"
@ -48,6 +48,7 @@ extern "C" {
#include "./mavlink_msg_sensor_offsets.h"
#include "./mavlink_msg_set_mag_offsets.h"
#include "./mavlink_msg_meminfo.h"
#include "./mavlink_msg_ap_adc.h"
#ifdef __cplusplus
}

View File

@ -0,0 +1,254 @@
// MESSAGE AP_ADC PACKING
#define MAVLINK_MSG_ID_AP_ADC 153
typedef struct __mavlink_ap_adc_t
{
uint16_t adc1; ///< ADC output 1
uint16_t adc2; ///< ADC output 2
uint16_t adc3; ///< ADC output 3
uint16_t adc4; ///< ADC output 4
uint16_t adc5; ///< ADC output 5
uint16_t adc6; ///< ADC output 6
} mavlink_ap_adc_t;
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
#define MAVLINK_MSG_ID_153_LEN 12
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
"AP_ADC", \
6, \
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
} \
}
/**
* @brief Pack a ap_adc message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message(msg, system_id, component_id, 12);
}
/**
* @brief Pack a ap_adc message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12);
}
/**
* @brief Encode a ap_adc struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ap_adc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
{
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12);
#endif
}
#endif
// MESSAGE AP_ADC UNPACKING
/**
* @brief Get field adc1 from ap_adc message
*
* @return ADC output 1
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field adc2 from ap_adc message
*
* @return ADC output 2
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field adc3 from ap_adc message
*
* @return ADC output 3
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field adc4 from ap_adc message
*
* @return ADC output 4
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field adc5 from ap_adc message
*
* @return ADC output 5
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field adc6 from ap_adc message
*
* @return ADC output 6
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
/**
* @brief Decode a ap_adc message into a struct
*
* @param msg The message to decode
* @param ap_adc C-struct to decode the message contents into
*/
static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
{
#if MAVLINK_NEED_BYTE_SWAP
ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
#else
memcpy(ap_adc, _MAV_PAYLOAD(msg), 12);
#endif
}

View File

@ -0,0 +1,210 @@
// MESSAGE AP_TIMING PACKING
#define MAVLINK_MSG_ID_AP_TIMING 155
typedef struct __mavlink_ap_timing_t
{
uint16_t min_50Hz_delta; ///< mininum delta for 50Hz loop
uint16_t max_50Hz_delta; ///< maximum delta for 50Hz loop
uint16_t min_200Hz_delta; ///< mininum delta for 200Hz loop
uint16_t max_200Hz_delta; ///< maximum delta for 200Hz loop
} mavlink_ap_timing_t;
#define MAVLINK_MSG_ID_AP_TIMING_LEN 8
#define MAVLINK_MSG_ID_155_LEN 8
#define MAVLINK_MESSAGE_INFO_AP_TIMING { \
"AP_TIMING", \
4, \
{ { "min_50Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_timing_t, min_50Hz_delta) }, \
{ "max_50Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_timing_t, max_50Hz_delta) }, \
{ "min_200Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_timing_t, min_200Hz_delta) }, \
{ "max_200Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_timing_t, max_200Hz_delta) }, \
} \
}
/**
* @brief Pack a ap_timing message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param min_50Hz_delta mininum delta for 50Hz loop
* @param max_50Hz_delta maximum delta for 50Hz loop
* @param min_200Hz_delta mininum delta for 200Hz loop
* @param max_200Hz_delta maximum delta for 200Hz loop
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_timing_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t min_50Hz_delta, uint16_t max_50Hz_delta, uint16_t min_200Hz_delta, uint16_t max_200Hz_delta)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint16_t(buf, 0, min_50Hz_delta);
_mav_put_uint16_t(buf, 2, max_50Hz_delta);
_mav_put_uint16_t(buf, 4, min_200Hz_delta);
_mav_put_uint16_t(buf, 6, max_200Hz_delta);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
#else
mavlink_ap_timing_t packet;
packet.min_50Hz_delta = min_50Hz_delta;
packet.max_50Hz_delta = max_50Hz_delta;
packet.min_200Hz_delta = min_200Hz_delta;
packet.max_200Hz_delta = max_200Hz_delta;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_TIMING;
return mavlink_finalize_message(msg, system_id, component_id, 8);
}
/**
* @brief Pack a ap_timing message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param min_50Hz_delta mininum delta for 50Hz loop
* @param max_50Hz_delta maximum delta for 50Hz loop
* @param min_200Hz_delta mininum delta for 200Hz loop
* @param max_200Hz_delta maximum delta for 200Hz loop
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_timing_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t min_50Hz_delta,uint16_t max_50Hz_delta,uint16_t min_200Hz_delta,uint16_t max_200Hz_delta)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint16_t(buf, 0, min_50Hz_delta);
_mav_put_uint16_t(buf, 2, max_50Hz_delta);
_mav_put_uint16_t(buf, 4, min_200Hz_delta);
_mav_put_uint16_t(buf, 6, max_200Hz_delta);
memcpy(_MAV_PAYLOAD(msg), buf, 8);
#else
mavlink_ap_timing_t packet;
packet.min_50Hz_delta = min_50Hz_delta;
packet.max_50Hz_delta = max_50Hz_delta;
packet.min_200Hz_delta = min_200Hz_delta;
packet.max_200Hz_delta = max_200Hz_delta;
memcpy(_MAV_PAYLOAD(msg), &packet, 8);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_TIMING;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
}
/**
* @brief Encode a ap_timing struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ap_timing C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_timing_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_timing_t* ap_timing)
{
return mavlink_msg_ap_timing_pack(system_id, component_id, msg, ap_timing->min_50Hz_delta, ap_timing->max_50Hz_delta, ap_timing->min_200Hz_delta, ap_timing->max_200Hz_delta);
}
/**
* @brief Send a ap_timing message
* @param chan MAVLink channel to send the message
*
* @param min_50Hz_delta mininum delta for 50Hz loop
* @param max_50Hz_delta maximum delta for 50Hz loop
* @param min_200Hz_delta mininum delta for 200Hz loop
* @param max_200Hz_delta maximum delta for 200Hz loop
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ap_timing_send(mavlink_channel_t chan, uint16_t min_50Hz_delta, uint16_t max_50Hz_delta, uint16_t min_200Hz_delta, uint16_t max_200Hz_delta)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint16_t(buf, 0, min_50Hz_delta);
_mav_put_uint16_t(buf, 2, max_50Hz_delta);
_mav_put_uint16_t(buf, 4, min_200Hz_delta);
_mav_put_uint16_t(buf, 6, max_200Hz_delta);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_TIMING, buf, 8);
#else
mavlink_ap_timing_t packet;
packet.min_50Hz_delta = min_50Hz_delta;
packet.max_50Hz_delta = max_50Hz_delta;
packet.min_200Hz_delta = min_200Hz_delta;
packet.max_200Hz_delta = max_200Hz_delta;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_TIMING, (const char *)&packet, 8);
#endif
}
#endif
// MESSAGE AP_TIMING UNPACKING
/**
* @brief Get field min_50Hz_delta from ap_timing message
*
* @return mininum delta for 50Hz loop
*/
static inline uint16_t mavlink_msg_ap_timing_get_min_50Hz_delta(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field max_50Hz_delta from ap_timing message
*
* @return maximum delta for 50Hz loop
*/
static inline uint16_t mavlink_msg_ap_timing_get_max_50Hz_delta(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field min_200Hz_delta from ap_timing message
*
* @return mininum delta for 200Hz loop
*/
static inline uint16_t mavlink_msg_ap_timing_get_min_200Hz_delta(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field max_200Hz_delta from ap_timing message
*
* @return maximum delta for 200Hz loop
*/
static inline uint16_t mavlink_msg_ap_timing_get_max_200Hz_delta(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Decode a ap_timing message into a struct
*
* @param msg The message to decode
* @param ap_timing C-struct to decode the message contents into
*/
static inline void mavlink_msg_ap_timing_decode(const mavlink_message_t* msg, mavlink_ap_timing_t* ap_timing)
{
#if MAVLINK_NEED_BYTE_SWAP
ap_timing->min_50Hz_delta = mavlink_msg_ap_timing_get_min_50Hz_delta(msg);
ap_timing->max_50Hz_delta = mavlink_msg_ap_timing_get_max_50Hz_delta(msg);
ap_timing->min_200Hz_delta = mavlink_msg_ap_timing_get_min_200Hz_delta(msg);
ap_timing->max_200Hz_delta = mavlink_msg_ap_timing_get_max_200Hz_delta(msg);
#else
memcpy(ap_timing, _MAV_PAYLOAD(msg), 8);
#endif
}

View File

@ -185,11 +185,65 @@ static void mavlink_test_meminfo(uint8_t system_id, uint8_t component_id, mavlin
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_ap_adc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ap_adc_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
};
mavlink_ap_adc_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.adc1 = packet_in.adc1;
packet1.adc2 = packet_in.adc2;
packet1.adc3 = packet_in.adc3;
packet1.adc4 = packet_in.adc4;
packet1.adc5 = packet_in.adc5;
packet1.adc6 = packet_in.adc6;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_ap_adc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_send(MAVLINK_COMM_1 , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
mavlink_test_meminfo(system_id, component_id, last_msg);
mavlink_test_ap_adc(system_id, component_id, last_msg);
}
#ifdef __cplusplus

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sun Sep 4 18:16:41 2011"
#define MAVLINK_BUILD_DATE "Sun Oct 16 13:23:41 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sun Sep 4 18:16:41 2011"
#define MAVLINK_BUILD_DATE "Sun Oct 16 13:23:42 2011"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101

View File

@ -0,0 +1,56 @@
/** @file
* @brief MAVLink comm protocol generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
#ifdef __cplusplus
extern "C" {
#endif
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 0, 28, 22, 22, 21, 0, 36, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 20, 32, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 0, 104, 244, 237, 222, 0, 158, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 160, 168, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247}
#endif
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, {NULL}, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_SHORT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE}
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_ARDUPILOTMEGA
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
// ENUM DEFINITIONS
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensor_offsets.h"
#include "./mavlink_msg_set_mag_offsets.h"
#include "./mavlink_msg_meminfo.h"
#include "./mavlink_msg_ap_adc.h"
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_H

View File

@ -0,0 +1,22 @@
/** @file
* @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wed Aug 24 17:14:16 2011
*/
#ifndef ARDUPILOTMEGA_TESTSUITE_H
#define ARDUPILOTMEGA_TESTSUITE_H
#ifdef __cplusplus
extern "C" {
#endif
static void mavtest_generate_outputs(mavlink_channel_t chan)
{
mavlink_msg_sensor_offsets_send(chan , 19107 , 19211 , 19315 , 17.0 , 963497672 , 963497880 , 101.0 , 129.0 , 157.0 , 185.0 , 213.0 , 241.0 );
mavlink_msg_set_mag_offsets_send(chan , 151 , 218 , 17235 , 17339 , 17443 );
}
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_TESTSUITE_H

View File

@ -0,0 +1,27 @@
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
#include "version.h"
#include "ardupilotmega.h"
#endif // MAVLINK_H

View File

@ -0,0 +1,254 @@
// MESSAGE AP_ADC PACKING
#define MAVLINK_MSG_ID_AP_ADC 153
typedef struct __mavlink_ap_adc_t
{
uint16_t adc1; ///< ADC output 1
uint16_t adc2; ///< ADC output 2
uint16_t adc3; ///< ADC output 3
uint16_t adc4; ///< ADC output 4
uint16_t adc5; ///< ADC output 5
uint16_t adc6; ///< ADC output 6
} mavlink_ap_adc_t;
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
#define MAVLINK_MSG_ID_153_LEN 12
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
"AP_ADC", \
6, \
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
} \
}
/**
* @brief Pack a ap_adc message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message(msg, system_id, component_id, 12, 188);
}
/**
* @brief Pack a ap_adc message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD(msg), &packet, 12);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 188);
}
/**
* @brief Encode a ap_adc struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ap_adc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
{
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12, 188);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12, 188);
#endif
}
#endif
// MESSAGE AP_ADC UNPACKING
/**
* @brief Get field adc1 from ap_adc message
*
* @return ADC output 1
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field adc2 from ap_adc message
*
* @return ADC output 2
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field adc3 from ap_adc message
*
* @return ADC output 3
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field adc4 from ap_adc message
*
* @return ADC output 4
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field adc5 from ap_adc message
*
* @return ADC output 5
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field adc6 from ap_adc message
*
* @return ADC output 6
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
/**
* @brief Decode a ap_adc message into a struct
*
* @param msg The message to decode
* @param ap_adc C-struct to decode the message contents into
*/
static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
{
#if MAVLINK_NEED_BYTE_SWAP
ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
#else
memcpy(ap_adc, _MAV_PAYLOAD(msg), 12);
#endif
}

Some files were not shown because too many files have changed in this diff Show More