Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • opensource/ardupilot
  • opensource/baitboat
2 results
Show changes
Commits on Source (1473)
Showing
with 450 additions and 411 deletions
......@@ -57,16 +57,19 @@ ArduCopter/test/*
ArduPlane/terrain/*.DAT
ArduPlane/test.ArduPlane/
APMrover2/test.APMrover2/
autotest.lck
build
Build.ArduCopter/*
Build.ArduPlane/*
Build.APMrover2/*
Build.AntennaTracker/*
cmake_install.cmake
CMakeCache.txt
CMakeFiles
config.mk
dataflash.bin
eeprom.bin
index.html
LASTLOG.TXT
Make.dep
mav.log
......
language: cpp
before_install:
- cd .. && ./ardupilot/Tools/scripts/install-prereqs-ubuntu.sh -y && . ~/.profile
- APMDIR=$(pwd) && pushd .. && $APMDIR/Tools/scripts/install-prereqs-ubuntu.sh -y && . ~/.profile && popd
script:
- cd ./ardupilot/ArduCopter && make configure && make && make px4-v2
- cd ../ArduPlane && make configure && make && make px4-v2
- cd ../APMrover2 && make configure && make && make px4-v2
- cd ../ArduCopter && make configure && make && make vrubrain-v51
- Tools/scripts/build_all_travis.sh
notifications:
webhooks:
urls:
- https://webhooks.gitter.im/e/e5e0b55e353e53945b4b
on_success: change # options: [always|never|change] default: always
on_failure: always # options: [always|never|change] default: always
on_start: false # default: false
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "ArduRover v2.46beta2"
#define THISFIRMWARE "ArduRover v2.47"
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
......@@ -112,6 +112,7 @@
#include <AP_Notify.h> // Notify library
#include <AP_BattMonitor.h> // Battery monitor library
#include <AP_OpticalFlow.h> // Optical Flow library
// Configuration
#include "config.h"
......@@ -200,21 +201,7 @@ static AP_GPS gps;
// flight modes convenience array
static AP_Int8 *modes = &g.mode1;
#if CONFIG_BARO == HAL_BARO_BMP085
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
static AP_Baro barometer;
#if CONFIG_COMPASS == HAL_COMPASS_PX4
static AP_Compass_PX4 compass;
......@@ -224,33 +211,17 @@ static AP_Compass_VRBRAIN compass;
static AP_Compass_HMC5843 compass;
#elif CONFIG_COMPASS == HAL_COMPASS_HIL
static AP_Compass_HIL compass;
#elif CONFIG_COMPASS == HAL_COMPASS_AK8963
static AP_Compass_AK8963_MPU9250 compass;
#else
#error Unrecognized CONFIG_COMPASS setting
#endif
#if CONFIG_INS_TYPE == HAL_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 apm1_adc;
#endif
#if CONFIG_INS_TYPE == HAL_INS_MPU6000
AP_InertialSensor_MPU6000 ins;
#elif CONFIG_INS_TYPE == HAL_INS_PX4
AP_InertialSensor_PX4 ins;
#elif CONFIG_INS_TYPE == HAL_INS_VRBRAIN
AP_InertialSensor_VRBRAIN ins;
#elif CONFIG_INS_TYPE == HAL_INS_HIL
AP_InertialSensor_HIL ins;
#elif CONFIG_INS_TYPE == HAL_INS_OILPAN
AP_InertialSensor_Oilpan ins( &apm1_adc );
#elif CONFIG_INS_TYPE == HAL_INS_FLYMAPLE
AP_InertialSensor_Flymaple ins;
#elif CONFIG_INS_TYPE == HAL_INS_L3G4200D
AP_InertialSensor_L3G4200D ins;
#elif CONFIG_INS_TYPE == HAL_INS_MPU9250
AP_InertialSensor_MPU9250 ins;
#else
#error Unrecognised CONFIG_INS_TYPE setting.
#endif // CONFIG_INS_TYPE
AP_InertialSensor ins;
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
......@@ -276,6 +247,8 @@ static bool verify_command(const AP_Mission::Mission_Command& cmd);
static void exit_mission();
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission);
static OpticalFlow optflow;
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
SITL sitl;
#endif
......@@ -566,6 +539,7 @@ void setup() {
// rover does not use arming nor pre-arm checks
AP_Notify::flags.armed = true;
AP_Notify::flags.pre_arm_check = true;
AP_Notify::flags.pre_arm_gps_check = true;
AP_Notify::flags.failsafe_battery = false;
notify.init(false);
......@@ -586,9 +560,8 @@ void setup() {
void loop()
{
// wait for an INS sample
if (!ins.wait_for_sample(1000)) {
return;
}
ins.wait_for_sample();
uint32_t timer = hal.scheduler->micros();
delta_us_fast_loop = timer - fast_loopTimer_us;
......@@ -652,7 +625,7 @@ static void mount_update(void)
static void update_alt()
{
barometer.read();
barometer.update();
if (should_log(MASK_LOG_IMU)) {
Log_Write_Baro();
}
......
......@@ -143,13 +143,17 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; // attitude stabilisation
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_YAW_POSITION; // yaw position
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; // X/Y position control
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; // motor control
break;
case INITIALISING:
break;
}
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
if (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS;
}
// default to all healthy except compass and gps which we set individually
control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS);
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
......@@ -158,11 +162,14 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
if (!ins.healthy()) {
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
if (!ins.get_gyro_health_all() || (!g.skip_gyro_cal && !ins.gyro_calibrated_ok_all())) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO;
}
if (!ins.get_accel_health_all()) {
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
}
if (!ahrs.healthy()) {
if (ahrs.initialised() && !ahrs.healthy()) {
// AHRS subsystem is unhealthy
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
......@@ -170,7 +177,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
int16_t battery_current = -1;
int8_t battery_remaining = -1;
if (battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) {
if (battery.has_current()) {
battery_remaining = battery.capacity_remaining_pct();
battery_current = battery.current_amps() * 100;
}
......@@ -509,6 +516,13 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
send_rangefinder(chan);
break;
case MSG_MOUNT_STATUS:
#if MOUNT == ENABLED
CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
camera_mount.status_msg(chan);
#endif // MOUNT == ENABLED
break;
case MSG_RAW_IMU2:
case MSG_LIMITS_STATUS:
case MSG_FENCE_STATUS:
......@@ -516,8 +530,21 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
// unused
break;
case MSG_BATTERY2:
CHECK_PAYLOAD_SIZE(BATTERY2);
gcs[chan-MAVLINK_COMM_0].send_battery2(battery);
break;
case MSG_CAMERA_FEEDBACK:
#if CAMERA == ENABLED
CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
camera.send_feedback(chan, gps, ahrs, current_loc);
#endif
break;
case MSG_RETRY_DEFERRED:
case MSG_TERRAIN:
case MSG_OPTICAL_FLOW:
break; // just here to prevent a warning
}
......@@ -739,6 +766,8 @@ GCS_MAVLINK::data_stream_send(void)
send_message(MSG_HWSTATUS);
send_message(MSG_RANGEFINDER);
send_message(MSG_SYSTEM_TIME);
send_message(MSG_BATTERY2);
send_message(MSG_MOUNT_STATUS);
}
}
......@@ -774,7 +803,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// 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 = MAV_RESULT_UNSUPPORTED;
......@@ -814,15 +842,17 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
packet.param2 == 1 ||
packet.param3 == 1) {
if ((packet.param1 == 1 ||
packet.param2 == 1) &&
packet.param3 == 0) {
startup_INS_ground(true);
}
if (packet.param4 == 1) {
result = MAV_RESULT_ACCEPTED;
} else if (packet.param4 == 1) {
trim_radio();
result = MAV_RESULT_ACCEPTED;
} else {
send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration"));
}
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
......@@ -911,29 +941,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_SET_MODE:
{
// decode
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// 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.
break;
}
switch (packet.custom_mode) {
case MANUAL:
case HOLD:
case LEARNING:
case STEERING:
case AUTO:
case RTL:
set_mode((enum mode)packet.custom_mode);
break;
}
handle_set_mode(msg, mavlink_set_mode);
break;
}
}
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
{
......@@ -958,6 +968,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
// mark the firmware version in the tlog
send_text_P(SEVERITY_LOW, PSTR(FIRMWARE_STRING));
#if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION)
send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION));
#endif
handle_param_request_list(msg);
break;
}
......@@ -1016,9 +1032,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
int16_t v[8];
mavlink_msg_rc_channels_override_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component))
break;
v[0] = packet.chan1_raw;
v[1] = packet.chan2_raw;
v[2] = packet.chan3_raw;
......@@ -1108,12 +1121,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
camera_mount.control_msg(msg);
break;
}
case MAVLINK_MSG_ID_MOUNT_STATUS:
{
camera_mount.status_msg(msg, chan);
break;
}
#endif // MOUNT == ENABLED
case MAVLINK_MSG_ID_RADIO:
......@@ -1145,19 +1152,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
#endif
default:
// forward unknown messages to the other link if there is one
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised && i != (uint8_t)chan) {
mavlink_channel_t out_chan = (mavlink_channel_t)i;
// only forward if it would fit in the transmit buffer
if (comm_get_txspace(out_chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
_mavlink_resend_uart(out_chan, msg);
}
}
}
break;
} // end switch
} // end handle mavlink
......
......@@ -319,7 +319,11 @@ static void Log_Write_Attitude()
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
#if AP_AHRS_NAVEKF_AVAILABLE
DataFlash.Log_Write_EKF(ahrs);
#if OPTFLOW == ENABLED
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
#else
DataFlash.Log_Write_EKF(ahrs,false);
#endif
DataFlash.Log_Write_AHRS2(ahrs);
#endif
}
......
......@@ -525,7 +525,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Group: BATT_
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT(battery, "BATT_", AP_BattMonitor),
GOBJECT(battery, "BATT", AP_BattMonitor),
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
......
......@@ -6,7 +6,7 @@
static void throttle_slew_limit(int16_t last_throttle)
{
// if slew limit rate is set to zero then do not slew limit
if (g.throttle_slewrate) {
if (g.throttle_slewrate && last_throttle != 0) {
// limit throttle change by the given percentage per second
float temp = g.throttle_slewrate * G_Dt * 0.01f * fabsf(channel_throttle->radio_max - channel_throttle->radio_min);
// allow a minimum change of 1 PWM per cycle
......@@ -143,7 +143,7 @@ static void calc_throttle(float target_speed)
float brake_gain = constrain_float(((-groundspeed_error)-g.braking_speederr)/g.braking_speederr, 0, 1);
int16_t braking_throttle = g.throttle_max * (g.braking_percent * 0.01f) * brake_gain;
channel_throttle->servo_out = constrain_int16(-braking_throttle, -g.throttle_max, -g.throttle_min);
// temporarily set us in reverse to allow the PWM setting to
// go negative
set_reverse(true);
......@@ -208,13 +208,12 @@ static void calc_nav_steer()
*****************************************/
static void set_servos(void)
{
int16_t last_throttle = channel_throttle->radio_out;
static int16_t last_throttle;
// support a separate steering channel
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_steering, channel_steer->pwm_to_angle_dz(0));
if ((control_mode == MANUAL || control_mode == LEARNING) &&
(g.skid_steer_out == g.skid_steer_in)) {
if (control_mode == MANUAL || control_mode == LEARNING) {
// do a direct pass through of radio values
channel_steer->radio_out = channel_steer->read();
channel_throttle->radio_out = channel_throttle->read();
......@@ -244,25 +243,28 @@ static void set_servos(void)
// limit throttle movement speed
throttle_slew_limit(last_throttle);
}
if (g.skid_steer_out) {
// convert the two radio_out values to skid steering values
/*
mixing rule:
steering = motor1 - motor2
throttle = 0.5*(motor1 + motor2)
motor1 = throttle + 0.5*steering
motor2 = throttle - 0.5*steering
*/
float steering_scaled = channel_steer->norm_output();
float throttle_scaled = channel_throttle->norm_output();
float motor1 = throttle_scaled + 0.5*steering_scaled;
float motor2 = throttle_scaled - 0.5*steering_scaled;
channel_steer->servo_out = 4500*motor1;
channel_throttle->servo_out = 100*motor2;
channel_steer->calc_pwm();
channel_throttle->calc_pwm();
}
// record last throttle before we apply skid steering
last_throttle = channel_throttle->radio_out;
if (g.skid_steer_out) {
// convert the two radio_out values to skid steering values
/*
mixing rule:
steering = motor1 - motor2
throttle = 0.5*(motor1 + motor2)
motor1 = throttle + 0.5*steering
motor2 = throttle - 0.5*steering
*/
float steering_scaled = channel_steer->norm_output();
float throttle_scaled = channel_throttle->norm_output();
float motor1 = throttle_scaled + 0.5*steering_scaled;
float motor2 = throttle_scaled - 0.5*steering_scaled;
channel_steer->servo_out = 4500*motor1;
channel_throttle->servo_out = 100*motor2;
channel_steer->calc_pwm();
channel_throttle->calc_pwm();
}
......
......@@ -308,6 +308,7 @@ static void do_take_picture()
{
#if CAMERA == ENABLED
camera.trigger_pic();
gcs_send_message(MSG_CAMERA_FEEDBACK);
if (should_log(MASK_LOG_CAMERA)) {
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
}
......
......@@ -51,7 +51,6 @@
//////////////////////////////////////////////////////////////////////////////
// sensor types
#define CONFIG_INS_TYPE HAL_INS_DEFAULT
#define CONFIG_BARO HAL_BARO_DEFAULT
#define CONFIG_COMPASS HAL_COMPASS_DEFAULT
......@@ -69,8 +68,6 @@
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
#undef CONFIG_BARO
#define CONFIG_BARO HAL_BARO_HIL
#undef CONFIG_INS_TYPE
#define CONFIG_INS_TYPE HAL_INS_HIL
#undef CONFIG_COMPASS
#define CONFIG_COMPASS HAL_COMPASS_HIL
#endif
......
......@@ -12,6 +12,10 @@ static void set_control_channels(void)
// set rc channel ranges
channel_steer->set_angle(SERVO_MAX);
channel_throttle->set_angle(100);
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
// take a proportion of speed.
hal.rcout->set_esc_scaling(channel_throttle->radio_min, channel_throttle->radio_max);
}
static void init_rc_in()
......
Release 2.47, November 15th 2014
--------------------------------
The ardupilot development team is proud to announce the release of
version 2.47 of APM:Rover. This is a minor bug fix release. The most
important change in this release is the fixing of the skid steering
support but there have been a number of fixes in other areas as well.
Full changes list for this release:
- add support for controlling safety switch on Pixhawk from ground station
- prevent reports of failed AHRS during initialisation
- fixed skid steering that was broken in the last release
- report gyro unhealthy if gyro calibration failed
- fixed dual sonar support in CLI sonar test
- fixed Nuttx crash on Pixhawk with bad I2C cables
- added GPS_SBAS_MODE parameter - turns on/off satellite based augemtation system for GPS
- added GPS_MIN_ELEV parameter - specifiy the elevation mask for GPS satellites
- added RELAY_DEFAULT parameter to control default of relay on startup
- fixed bug in FRAM storage on Pixhawk that could cause parameters changes not to be saved
- better handling of compass errors in the EKF (Extended Kalman Filter)
- improved support for linux based autopilots
- added support for PulsedLight LIDAR as a range finder
Many thanks to everyone who contributed to this release, especially
Tom Coyle and Linus Penzlien for their excellent testing and feedback.
Happy driving!
Release 2.46, August 26th 2014
------------------------------
The ardupilot development team is proud to announce the release of
version 2.46 of APM:Rover. This is a major release with a lot of new
features and bug fixes.
This release is based on a lot of development and testing that
happened prior to the AVC competition where APM based vehicles
performed very well.
Full changes list for this release:
- added support for higher baudrates on telemetry ports, to make it
easier to use high rate telemetry to companion boards. Rates of up
to 1.5MBit are now supported to companion boards.
- new Rangefinder code with support for a wider range of rangefinder
types including a range of Lidars (thanks to Allyson Kreft)
- added logging of power status on Pixhawk
- added PIVOT_TURN_ANGLE parameter for pivot based turns on skid
steering rovers
- lots of improvements to the EKF support for Rover, thanks to Paul
Riseborough and testing from Tom Coyle. Using the EKF can greatly
improve navigation accuracy for fast rovers. Enable with
AHRS_EKF_USE=1.
- improved support for dual GPS on Pixhawk. Using a 2nd GPS can
greatly improve performance when in an area with an obstructed
view of the sky
- support for up to 14 RC channels on Pihxawk
- added BRAKING_PERCENT and BRAKING_SPEEDERR parameters for better
breaking support when cornering
- added support for FrSky telemetry via SERIAL2_PROTOCOL parameter
(thanks to Matthias Badaire)
- added support for Linux based autopilots, initially with the PXF
BeagleBoneBlack cape and the Erle robotics board. Support for more
boards is expected in future releases. Thanks to Victor, Sid and
Anuj for their great work on the Linux port.
- added StorageManager library, which expands available FRAM storage
on Pixhawk to 16 kByte. This allows for 724 waypoints, 50 rally
points and 84 fence points on Pixhawk.
- improved reporting of magnetometer and barometer errors to the GCS
- fixed a bug in automatic flow control detection for serial ports
in Pixhawk
- fixed use of FMU servo pins as digital inputs on Pixhawk
- imported latest updates for VRBrain boards (thanks to Emile
Castelnuovo and Luca Micheletti)
- updates to the Piksi GPS support (thanks to Niels Joubert)
- improved gyro estimate in DCM (thanks to Jon Challinger)
- improved position projection in DCM in wind (thanks to Przemek
Lekston)
- several updates to AP_NavEKF for more robust handling of errors
(thanks to Paul Riseborough)
- lots of small code cleanups thanks to Daniel Frenzel
- initial support for NavIO board from Mikhail Avkhimenia
- fixed logging of RCOU for up to 12 channels (thanks to Emile
Castelnuovo)
- code cleanups from Silvia Nunezrivero
- improved parameter download speed on radio links with no flow
control
Many thanks to everyone who contributed to this release, especially
Tom Coyle and Linus Penzlien for their excellent testing and feedback.
Happy driving!
......@@ -341,9 +341,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
mode != AUTO &&
mode != RTL)
{
if (mode < MANUAL)
mode = RTL;
else if (mode > RTL)
if (mode > RTL)
mode = MANUAL;
else
mode += radioInputSwitch;
......@@ -467,9 +465,13 @@ static void report_batt_monitor()
//print_blanks(2);
cliSerial->printf_P(PSTR("Batt Mointor\n"));
print_divider();
if(battery.monitoring() == AP_BATT_MONITOR_DISABLED) cliSerial->printf_P(PSTR("Batt monitoring disabled"));
if(battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_ONLY) cliSerial->printf_P(PSTR("Monitoring batt volts"));
if(battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) cliSerial->printf_P(PSTR("Monitoring volts and current"));
if (battery.num_instances() == 0) {
cliSerial->printf_P(PSTR("Batt monitoring disabled"));
} else if (!battery.has_current()) {
cliSerial->printf_P(PSTR("Monitoring batt volts"));
} else {
cliSerial->printf_P(PSTR("Monitoring volts and current"));
}
print_blanks(2);
}
static void report_radio()
......@@ -652,7 +654,6 @@ radio_input_switch(void)
static void zero_eeprom(void)
{
uint8_t b = 0;
cliSerial->printf_P(PSTR("\nErasing EEPROM\n"));
StorageManager::erase();
cliSerial->printf_P(PSTR("done\n"));
......
......@@ -189,10 +189,6 @@ static void init_ardupilot()
// Do GPS init
gps.init(&DataFlash);
//mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav
mavlink_system.compid = 1; //MAV_COMP_ID_IMU; // We do not check for comp id
mavlink_system.type = MAV_TYPE_GROUND_ROVER;
rc_override_active = hal.rcin->set_overrides(rc_override, 8);
init_rc_in(); // sets up rc channels from radio
......@@ -262,6 +258,7 @@ static void startup_ground(void)
mission.init();
hal.uartA->set_blocking_writes(false);
hal.uartB->set_blocking_writes(false);
hal.uartC->set_blocking_writes(false);
gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to drive."));
......@@ -324,6 +321,24 @@ static void set_mode(enum mode mode)
}
}
/*
set_mode() wrapper for MAVLink SET_MODE
*/
static bool mavlink_set_mode(uint8_t mode)
{
switch (mode) {
case MANUAL:
case HOLD:
case LEARNING:
case STEERING:
case AUTO:
case RTL:
set_mode((enum mode)mode);
return true;
}
return false;
}
/*
called to set/unset a failsafe event.
*/
......
......@@ -349,7 +349,7 @@ test_ins(uint8_t argc, const Menu::arg *argv)
uint8_t medium_loopCounter = 0;
while(1){
ins.wait_for_sample(1000);
ins.wait_for_sample();
ahrs.update();
......@@ -371,9 +371,9 @@ test_ins(uint8_t argc, const Menu::arg *argv)
(uint16_t)ahrs.yaw_sensor / 100,
gyros.x, gyros.y, gyros.z,
accels.x, accels.y, accels.z);
}
if(cliSerial->available() > 0){
return (0);
if(cliSerial->available() > 0){
return (0);
}
}
}
......@@ -409,7 +409,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
uint8_t medium_loopCounter = 0;
while(1) {
ins.wait_for_sample(1000);
ins.wait_for_sample();
ahrs.update();
medium_loopCounter++;
......@@ -455,12 +455,15 @@ test_mag(uint8_t argc, const Menu::arg *argv)
static int8_t
test_sonar(uint8_t argc, const Menu::arg *argv)
{
init_sonar();
delay(20);
sonar.update();
if (!sonar.healthy()) {
cliSerial->println_P(PSTR("WARNING: Sonar is not enabled"));
}
print_hit_enter();
init_sonar();
float sonar_dist_cm_min = 0.0f;
float sonar_dist_cm_max = 0.0f;
......@@ -472,8 +475,9 @@ test_sonar(uint8_t argc, const Menu::arg *argv)
while (true) {
delay(20);
sonar.update();
uint32_t now = millis();
float dist_cm = sonar.distance_cm(0);
float voltage = sonar.voltage_mv(0);
if (sonar_dist_cm_min == 0.0f) {
......
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define THISFIRMWARE "AntennaTracker V0.1"
#define THISFIRMWARE "AntennaTracker V0.2"
/*
Lead developers: Matthew Ridley and Andrew Tridgell
......@@ -62,6 +62,7 @@
#include <AP_Airspeed.h>
#include <RC_Channel.h>
#include <AP_BoardConfig.h>
#include <AP_OpticalFlow.h>
// Configuration
#include "config.h"
......@@ -102,20 +103,6 @@ static AP_Scheduler scheduler;
// notification object for LEDs, buzzers etc
static AP_Notify notify;
// tracking status for MAVLink
static struct {
float bearing;
float distance;
float pitch;
float altitude_difference;
float altitude_offset;
bool manual_control_yaw:1;
bool manual_control_pitch:1;
bool need_altitude_calibration:1;
bool scan_reverse_pitch:1;
bool scan_reverse_yaw:1;
} nav_status;
static uint32_t start_time_ms;
static bool usb_connected;
......@@ -130,21 +117,7 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...);
////////////////////////////////////////////////////////////////////////////////
static AP_GPS gps;
#if CONFIG_BARO == HAL_BARO_BMP085
static AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == HAL_BARO_PX4
static AP_Baro_PX4 barometer;
#elif CONFIG_BARO == HAL_BARO_VRBRAIN
static AP_Baro_VRBRAIN barometer;
#elif CONFIG_BARO == HAL_BARO_HIL
static AP_Baro_HIL barometer;
#elif CONFIG_BARO == HAL_BARO_MS5611
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c);
#elif CONFIG_BARO == HAL_BARO_MS5611_SPI
static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi);
#else
#error Unrecognized CONFIG_BARO setting
#endif
static AP_Baro barometer;
#if CONFIG_COMPASS == HAL_COMPASS_PX4
static AP_Compass_PX4 compass;
......@@ -154,33 +127,17 @@ static AP_Compass_VRBRAIN compass;
static AP_Compass_HMC5843 compass;
#elif CONFIG_COMPASS == HAL_COMPASS_HIL
static AP_Compass_HIL compass;
#elif CONFIG_COMPASS == HAL_COMPASS_AK8963
static AP_Compass_AK8963_MPU9250 compass;
#else
#error Unrecognized CONFIG_COMPASS setting
#endif
#if CONFIG_INS_TYPE == HAL_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 apm1_adc;
#endif
#if CONFIG_INS_TYPE == HAL_INS_MPU6000
AP_InertialSensor_MPU6000 ins;
#elif CONFIG_INS_TYPE == HAL_INS_PX4
AP_InertialSensor_PX4 ins;
#elif CONFIG_INS_TYPE == HAL_INS_VRBRAIN
AP_InertialSensor_VRBRAIN ins;
#elif CONFIG_INS_TYPE == HAL_INS_HIL
AP_InertialSensor_HIL ins;
#elif CONFIG_INS_TYPE == HAL_INS_OILPAN
AP_InertialSensor_Oilpan ins( &apm1_adc );
#elif CONFIG_INS_TYPE == HAL_INS_FLYMAPLE
AP_InertialSensor_Flymaple ins;
#elif CONFIG_INS_TYPE == HAL_INS_L3G4200D
AP_InertialSensor_L3G4200D ins;
#elif CONFIG_INS_TYPE == HAL_INS_MPU9250
AP_InertialSensor_MPU9250 ins;
#else
#error Unrecognised CONFIG_INS_TYPE setting.
#endif // CONFIG_INS_TYPE
AP_InertialSensor ins;
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
......@@ -196,8 +153,8 @@ SITL sitl;
/**
antenna control channels
*/
static RC_Channel channel_yaw(CH_1);
static RC_Channel channel_pitch(CH_2);
static RC_Channel channel_yaw(CH_YAW);
static RC_Channel channel_pitch(CH_PITCH);
////////////////////////////////////////////////////////////////////////////////
// GCS selection
......@@ -205,10 +162,6 @@ static RC_Channel channel_pitch(CH_2);
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
// If proxy_mode is enabled, uartC is connected to a remote vehicle,
// not gcs[1]
static GCS_MAVLINK proxy_vehicle;
// board specific config
static AP_BoardConfig BoardConfig;
......@@ -222,6 +175,45 @@ static struct Location current_loc;
// There are multiple states defined such as MANUAL, FBW-A, AUTO
static enum ControlMode control_mode = INITIALISING;
////////////////////////////////////////////////////////////////////////////////
// Vehicle state
////////////////////////////////////////////////////////////////////////////////
static struct {
bool location_valid; // true if we have a valid location for the vehicle
Location location; // lat, long in degrees * 10^7; alt in meters * 100
Location location_estimate; // lat, long in degrees * 10^7; alt in meters * 100
uint32_t last_update_us; // last position update in micxroseconds
uint32_t last_update_ms; // last position update in milliseconds
float heading; // last known direction vehicle is moving
float ground_speed; // vehicle's last known ground speed in m/s
} vehicle;
////////////////////////////////////////////////////////////////////////////////
// Navigation controller state
////////////////////////////////////////////////////////////////////////////////
static struct {
float bearing; // bearing to vehicle in centi-degrees
float distance; // distance to vehicle in meters
float pitch; // pitch to vehicle in degrees (positive means vehicle is above tracker, negative means below)
float altitude_difference; // altitude difference between tracker and vehicle in meters. positive value means vehicle is above tracker
float altitude_offset; // offset in meters which is added to tracker altitude to align altitude measurements with vehicle's barometer
bool manual_control_yaw : 1;// true if tracker yaw is under manual control
bool manual_control_pitch : 1;// true if tracker pitch is manually controlled
bool need_altitude_calibration : 1;// true if tracker altitude has not been determined (true after startup)
bool scan_reverse_pitch : 1;// controls direction of pitch movement in SCAN mode
bool scan_reverse_yaw : 1;// controls direction of yaw movement in SCAN mode
} nav_status;
////////////////////////////////////////////////////////////////////////////////
// Servo state
////////////////////////////////////////////////////////////////////////////////
static struct {
bool yaw_lower : 1; // true if yaw servo has been limited from moving to a lower position (i.e. position or rate limited)
bool yaw_upper : 1; // true if yaw servo has been limited from moving to a higher position (i.e. position or rate limited)
bool pitch_lower : 1; // true if pitch servo has been limited from moving to a lower position (i.e. position or rate limited)
bool pitch_upper : 1; // true if pitch servo has been limited from moving to a higher position (i.e. position or rate limited)
} servo_limit;
/*
scheduler table - all regular tasks apart from the fast_loop()
should be listed here, along with how often they should be called
......@@ -230,6 +222,7 @@ static enum ControlMode control_mode = INITIALISING;
*/
static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ update_ahrs, 1, 1000 },
{ read_radio, 1, 200 },
{ update_tracking, 1, 1000 },
{ update_GPS, 5, 4000 },
{ update_compass, 5, 1500 },
......@@ -257,9 +250,9 @@ void setup()
// load the default values of variables listed in var_info[]
AP_Param::setup_sketch_defaults();
// arduplane does not use arming nor pre-arm checks
AP_Notify::flags.armed = true;
// antenna tracker does not use pre-arm checks or battery failsafe
AP_Notify::flags.pre_arm_check = true;
AP_Notify::flags.pre_arm_gps_check = true;
AP_Notify::flags.failsafe_battery = false;
notify.init(false);
......@@ -275,9 +268,7 @@ void setup()
void loop()
{
// wait for an INS sample
if (!ins.wait_for_sample(1000)) {
return;
}
ins.wait_for_sample();
// tell the scheduler one tick has passed
scheduler.tick();
......@@ -296,10 +287,13 @@ static void one_second_loop()
// sync MAVLink system ID
mavlink_system.sysid = g.sysid_this_mav;
// updated armed/disarmed status LEDs
update_armed_disarmed();
static uint8_t counter;
counter++;
if (counter >= 60) {
if (counter >= 60) {
if(g.compass_enabled) {
compass.save_offsets();
}
......
......@@ -193,6 +193,11 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
gcs[chan-MAVLINK_COMM_0].send_gps_raw(gps);
break;
case MSG_RADIO_IN:
CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
gcs[chan-MAVLINK_COMM_0].send_radio_in(0);
break;
case MSG_RADIO_OUT:
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
send_radio_out(chan);
......@@ -249,12 +254,16 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
case MSG_RETRY_DEFERRED:
case MSG_CURRENT_WAYPOINT:
case MSG_VFR_HUD:
case MSG_RADIO_IN:
case MSG_SYSTEM_TIME:
case MSG_LIMITS_STATUS:
case MSG_FENCE_STATUS:
case MSG_WIND:
case MSG_RANGEFINDER:
case MSG_TERRAIN:
case MSG_BATTERY2:
case MSG_CAMERA_FEEDBACK:
case MSG_MOUNT_STATUS:
case MSG_OPTICAL_FLOW:
break; // just here to prevent a warning
}
return true;
......@@ -418,6 +427,7 @@ GCS_MAVLINK::data_stream_send(void)
}
if (stream_trigger(STREAM_RC_CHANNELS)) {
send_message(MSG_RADIO_IN);
send_message(MSG_RADIO_OUT);
}
......@@ -432,73 +442,41 @@ GCS_MAVLINK::data_stream_send(void)
}
}
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
/*
We eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and
MAVLINK_MSG_ID_SCALED_PRESSUREs
*/
void mavlink_snoop(const mavlink_message_t* msg)
{
if (g.proxy_mode == true)
switch (msg->msgid) {
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
{
if (chan == proxy_vehicle.chan)
{
// From the remote vehicle.
// All messages from the remote are proxied to GCS
// We also eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and MAVLINK_MSG_ID_SCALED_PRESSUREs
switch (msg->msgid)
{
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
{
// decode
mavlink_global_position_int_t packet;
mavlink_msg_global_position_int_decode(msg, &packet);
tracking_update_position(packet);
break;
}
case MAVLINK_MSG_ID_SCALED_PRESSURE:
{
// decode
mavlink_scaled_pressure_t packet;
mavlink_msg_scaled_pressure_decode(msg, &packet);
tracking_update_pressure(packet);
break;
}
}
// Proxy to all the GCS stations
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
mavlink_channel_t out_chan = (mavlink_channel_t)i;
// only forward if it would fit in the transmit buffer
if (comm_get_txspace(out_chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
_mavlink_resend_uart(out_chan, msg);
}
}
}
}
// Else its from the GCS, and it might be for the remote and.or it might be for the tracker
// So we fall through to the below
// decode
mavlink_global_position_int_t packet;
mavlink_msg_global_position_int_decode(msg, &packet);
tracking_update_position(packet);
break;
}
case MAVLINK_MSG_ID_SCALED_PRESSURE:
{
// decode
mavlink_scaled_pressure_t packet;
mavlink_msg_scaled_pressure_decode(msg, &packet);
tracking_update_pressure(packet);
break;
}
}
}
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
{
switch (msg->msgid) {
// If we are currently operating as a proxy for a remote,
// alas we have to look inside each packet to see if its for us or for the remote
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
{
if (g.proxy_mode == true && proxy_vehicle.initialised)
{
// See if its for the remote
mavlink_request_data_stream_t packet;
mavlink_msg_request_data_stream_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component))
{
// Not for us, must be for the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
break;
}
// Else its for us, the tracker
}
handle_request_data_stream(msg, true);
break;
}
......@@ -506,92 +484,30 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
{
if (g.proxy_mode == true && proxy_vehicle.initialised)
{
// See if its for the remote
mavlink_param_request_list_t packet;
mavlink_msg_param_request_list_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component))
{
// Not for us, must be for the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
break;
}
// Else its for us, the tracker
}
handle_param_request_list(msg);
break;
}
case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
{
if (g.proxy_mode == true && proxy_vehicle.initialised)
{
// See if its for the remote
mavlink_param_request_read_t packet;
mavlink_msg_param_request_read_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component))
{
// Not for us, must be for the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
break;
}
// Else its for us, the tracker
}
handle_param_request_read(msg);
break;
}
case MAVLINK_MSG_ID_PARAM_SET:
{
if (g.proxy_mode == true && proxy_vehicle.initialised)
{
// See if its for the remote
mavlink_param_set_t packet;
mavlink_msg_param_set_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component))
{
// Not for us, must be for the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
break;
}
// Else its for us, the tracker
}
handle_param_set(msg, NULL);
break;
}
case MAVLINK_MSG_ID_HEARTBEAT:
{
// Heartbeats are always proxied to the remote and also handled locally
if (g.proxy_mode == true && proxy_vehicle.initialised)
{
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
if (msg->sysid != g.sysid_my_gcs) break;
break;
}
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)) {
// Its for the remote, proxy it
if (g.proxy_mode == true && proxy_vehicle.initialised) {
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
break;
}
uint8_t result = MAV_RESULT_UNSUPPORTED;
......@@ -695,14 +611,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// decode
mavlink_mission_write_partial_list_t packet;
mavlink_msg_mission_write_partial_list_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) {
if (g.proxy_mode == true && proxy_vehicle.initialised) {
// Its for the remote, proxy it
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
break;
}
if (packet.start_index == 0)
{
// New home at wp index 0. Ask for it
......@@ -723,14 +631,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
uint8_t result = MAV_MISSION_ACCEPTED;
mavlink_msg_mission_item_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) {
if (g.proxy_mode == true && proxy_vehicle.initialised) {
// Its for the remote, proxy it
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
break;
}
struct Location tell_command = {};
......@@ -813,13 +713,6 @@ mission_failed:
{
mavlink_manual_control_t packet;
mavlink_msg_manual_control_decode(msg, &packet);
if (g.proxy_mode == true && proxy_vehicle.initialised) {
// Also proxy it to the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
if(msg->sysid != g.sysid_my_gcs) break; // Only accept control from our gcs
tracking_manual_control(packet);
break;
}
......@@ -829,11 +722,6 @@ mission_failed:
// decode
mavlink_global_position_int_t packet;
mavlink_msg_global_position_int_decode(msg, &packet);
if (g.proxy_mode == true && proxy_vehicle.initialised) {
// Also proxy it to the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
tracking_update_position(packet);
break;
}
......@@ -843,41 +731,13 @@ mission_failed:
// decode
mavlink_scaled_pressure_t packet;
mavlink_msg_scaled_pressure_decode(msg, &packet);
if (g.proxy_mode == true && proxy_vehicle.initialised) {
// Also proxy it to the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
tracking_update_pressure(packet);
break;
}
case MAVLINK_MSG_ID_SET_MODE:
{
// decode
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
if (g.proxy_mode == true && proxy_vehicle.initialised) {
// Also proxy it to the remote
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// 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.
break;
}
switch (packet.custom_mode) {
case MANUAL:
case STOP:
case SCAN:
case AUTO:
set_mode((enum ControlMode)packet.custom_mode);
break;
}
handle_set_mode(msg, mavlink_set_mode);
break;
}
......@@ -887,14 +747,6 @@ mission_failed:
break;
#endif
default:
// Proxy all other messages to the remote
if (g.proxy_mode && proxy_vehicle.initialised) {
if (comm_get_txspace(proxy_vehicle.chan) > ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES)
_mavlink_resend_uart(proxy_vehicle.chan, msg);
}
break;
} // end switch
} // end handle mavlink
......@@ -965,10 +817,6 @@ static void gcs_update(void)
gcs[i].update(NULL);
}
}
// Also check for messages from the remote if we are in proxy mode
if (g.proxy_mode == true && proxy_vehicle.initialised) {
proxy_vehicle.update(NULL);
}
}
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
......
......@@ -80,7 +80,7 @@ public:
k_param_BoardConfig,
k_param_gps,
k_param_scan_speed,
k_param_proxy_mode,
k_param_proxy_mode_unused, // deprecated
k_param_servo_type,
k_param_onoff_yaw_rate,
k_param_onoff_pitch_rate,
......@@ -88,6 +88,8 @@ public:
k_param_onoff_pitch_mintime,
k_param_yaw_trim,
k_param_pitch_trim,
k_param_yaw_range,
k_param_pitch_range, // 136
k_param_channel_yaw = 200,
k_param_channel_pitch,
......@@ -124,7 +126,6 @@ public:
AP_Float start_longitude;
AP_Float startup_delay;
AP_Int8 proxy_mode;
AP_Int8 servo_type;
AP_Float onoff_yaw_rate;
AP_Float onoff_pitch_rate;
......@@ -132,6 +133,8 @@ public:
AP_Float onoff_pitch_mintime;
AP_Float yaw_trim;
AP_Float pitch_trim;
AP_Int16 yaw_range; // yaw axis total range of motion in degrees
AP_Int16 pitch_range; // pitch axis total range of motion in degrees
// Waypoints
//
......
......@@ -122,19 +122,10 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(startup_delay, "STARTUP_DELAY", 0),
// @Param: PROXY_MODE
// @DisplayName: Also act as a MAVLink proxy for a vehicle
// @Description: If true, the tracker will act as a MAVlink proxy for a remote vehicle, and will eavesdrop vehicle position reports.
// @Units: boolean
// @Increment: 1
// @Range: 0 1
// @User: Standard
GSCALAR(proxy_mode, "PROXY_MODE", 0),
// @Param: SERVO_TYPE
// @DisplayName: Type of servo system being used
// @Description: This allows selection of position servos or on/off servos
// @Values: Position:0,OnOff:1
// @Values: 0:Position,1:OnOff
// @User: Standard
GSCALAR(servo_type, "SERVO_TYPE", SERVO_TYPE_POSITION),
......@@ -192,6 +183,24 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Standard
GSCALAR(pitch_trim, "PITCH_TRIM", 0),
// @Param: YAW_RANGE
// @DisplayName: Yaw Angle Range
// @Description: Yaw axis total range of motion in degrees
// @Units: degrees
// @Increment: 0.1
// @Range: 0 360
// @User: Standard
GSCALAR(yaw_range, "YAW_RANGE", YAW_RANGE_DEFAULT),
// @Param: PITCH_RANGE
// @DisplayName: Pitch Range
// @Description: Pitch axis total range of motion in degrees
// @Units: degrees
// @Increment: 0.1
// @Range: 0 180
// @User: Standard
GSCALAR(pitch_range, "PITCH_RANGE", PITCH_RANGE_DEFAULT),
// barometer ground calibration. The GND_ prefix is chosen for
// compatibility with previous releases of ArduPlane
// @Group: GND_
......
......@@ -17,7 +17,6 @@
#define ENABLE ENABLED
#define DISABLE DISABLED
#define CONFIG_INS_TYPE HAL_INS_DEFAULT
#define CONFIG_BARO HAL_BARO_DEFAULT
#define CONFIG_COMPASS HAL_COMPASS_DEFAULT
......@@ -55,6 +54,37 @@
# define SERIAL2_BUFSIZE 256
#endif
//////////////////////////////////////////////////////////////////////////////
// RC Channel definitions
//
#ifndef CH_YAW
# define CH_YAW CH_1 // RC input/output for yaw on channel 1
#endif
#ifndef CH_PITCH
# define CH_PITCH CH_2 // RC input/output for pitch on channel 2
#endif
//////////////////////////////////////////////////////////////////////////////
// yaw and pitch axis angle range defaults
//
#ifndef YAW_RANGE_DEFAULT
# define YAW_RANGE_DEFAULT 360
#endif
#ifndef PITCH_RANGE_DEFAULT
# define PITCH_RANGE_DEFAULT 180
#endif
//////////////////////////////////////////////////////////////////////////////
// Tracking definitions
//
#ifndef TRACKING_TIMEOUT_MS
# define TRACKING_TIMEOUT_MS 5000 // consider we've lost track of vehicle after 5 seconds with no position update. Used to update armed/disarmed status leds
#endif
#ifndef TRACKING_TIMEOUT_SEC
# define TRACKING_TIMEOUT_SEC 5.0f // consider we've lost track of vehicle after 5 seconds with no position update.
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//
......
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* control_auto.pde - auto control mode
*/
/*
* update_auto - runs the auto controller
* called at 50hz while control_mode is 'AUTO'
*/
static void update_auto(void)
{
// exit immediately if we do not have a valid vehicle position
if (!vehicle.location_valid) {
return;
}
float yaw = wrap_180_cd((nav_status.bearing+g.yaw_trim)*100) * 0.01f;
float pitch = constrain_float(nav_status.pitch+g.pitch_trim, -90, 90);
update_pitch_servo(pitch);
update_yaw_servo(yaw);
}