Browse Source

Plane: fixes for new AP_Relay interface

mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
b6295c12e1
  1. 9
      ArduPlane/ArduPlane.pde
  2. 6
      ArduPlane/GCS_Mavlink.pde
  3. 5
      ArduPlane/Parameters.h
  4. 2
      ArduPlane/Parameters.pde
  5. 8
      ArduPlane/config.h
  6. 3
      ArduPlane/defines.h
  7. 2
      ArduPlane/events.pde
  8. 2
      ArduPlane/system.pde
  9. 6
      ArduPlane/test.pde

9
ArduPlane/ArduPlane.pde

@ -236,11 +236,12 @@ AP_HAL::AnalogSource * batt_curr_pin; @@ -236,11 +236,12 @@ AP_HAL::AnalogSource * batt_curr_pin;
////////////////////////////////////////////////////////////////////////////////
// Relay
////////////////////////////////////////////////////////////////////////////////
#if CONFIG_RELAY == ENABLED
AP_Relay relay;
#endif
// Camera
#if CAMERA == ENABLED
AP_Camera camera(&relay);
#endif
////////////////////////////////////////////////////////////////////////////////
// Global variables
@ -784,7 +785,7 @@ static void medium_loop() @@ -784,7 +785,7 @@ static void medium_loop()
#endif
#if CAMERA == ENABLED
g.camera.trigger_pic_cleanup();
camera.trigger_pic_cleanup();
#endif
// This is the start of the medium (10 Hz) loop pieces

6
ArduPlane/GCS_Mavlink.pde

@ -505,7 +505,7 @@ static void NOINLINE send_statustext(mavlink_channel_t chan) @@ -505,7 +505,7 @@ static void NOINLINE send_statustext(mavlink_channel_t chan)
static bool telemetry_delayed(mavlink_channel_t chan)
{
uint32_t tnow = millis() >> 10;
if (tnow > g.telem_delay) {
if (tnow > (uint32_t)g.telem_delay) {
return false;
}
#if USB_MUX_PIN > 0
@ -1847,13 +1847,13 @@ mission_failed: @@ -1847,13 +1847,13 @@ mission_failed:
#if CAMERA == ENABLED
case MAVLINK_MSG_ID_DIGICAM_CONFIGURE:
{
g.camera.configure_msg(msg);
camera.configure_msg(msg);
break;
}
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
{
g.camera.control_msg(msg);
camera.control_msg(msg);
break;
}
#endif // CAMERA == ENABLED

5
ArduPlane/Parameters.h

@ -354,11 +354,6 @@ public: @@ -354,11 +354,6 @@ public:
AP_Int8 stick_mixing;
AP_Int8 rudder_steer;
// Camera
#if CAMERA == ENABLED
AP_Camera camera;
#endif
// RC channels
RC_Channel channel_roll;
RC_Channel channel_pitch;

2
ArduPlane/Parameters.pde

@ -588,7 +588,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -588,7 +588,7 @@ const AP_Param::Info var_info[] PROGMEM = {
#if CAMERA == ENABLED
// @Group: CAM_
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
GGROUP(camera, "CAM_", AP_Camera),
GOBJECT(camera, "CAM_", AP_Camera),
#endif
// RC channel

8
ArduPlane/config.h

@ -62,9 +62,6 @@ @@ -62,9 +62,6 @@
// default choices for a 1280. We can't fit everything in, so we
// make some popular choices by default
#define LOGGING_ENABLED DISABLED
#ifndef CONFIG_RELAY
# define CONFIG_RELAY DISABLED
#endif
#ifndef GEOFENCE_ENABLED
# define GEOFENCE_ENABLED DISABLED
#endif
@ -98,9 +95,6 @@ @@ -98,9 +95,6 @@
# define LED_ON HIGH
# define LED_OFF LOW
# define USB_MUX_PIN -1
#ifndef CONFIG_RELAY
# define CONFIG_RELAY ENABLED
#endif
# define BATTERY_VOLT_PIN 0 // Battery voltage on A0
# define BATTERY_CURR_PIN 1 // Battery current on A1
# define CONFIG_INS_TYPE CONFIG_INS_OILPAN
@ -117,7 +111,6 @@ @@ -117,7 +111,6 @@
#else
# define USB_MUX_PIN 23
#endif
# define CONFIG_RELAY DISABLED
# define BATTERY_VOLT_PIN 1 // Battery voltage on A1
# define BATTERY_CURR_PIN 2 // Battery current on A2
# define CONFIG_INS_TYPE CONFIG_INS_MPU6000
@ -135,7 +128,6 @@ @@ -135,7 +128,6 @@
# define C_LED_PIN 25
# define LED_ON LOW
# define LED_OFF HIGH
# define CONFIG_RELAY DISABLED
# define BATTERY_VOLT_PIN 1 // Battery voltage on A1
# define BATTERY_CURR_PIN 2 // Battery current on A2
# define CONFIG_INS_TYPE CONFIG_INS_STUB

3
ArduPlane/defines.h

@ -187,9 +187,6 @@ enum gcs_severity { @@ -187,9 +187,6 @@ enum gcs_severity {
#define BATTERY_VOLTAGE(x) (x*(g.input_voltage/1024.0))*g.volt_div_ratio
#define CURRENT_AMPS(x) ((x*(g.input_voltage/1024.0))-g.curr_amp_offset)*g.curr_amp_per_volt
#define RELAY_PIN 47
#define AN4 4
#define AN5 5

2
ArduPlane/events.pde

@ -116,9 +116,7 @@ static void update_events(void) @@ -116,9 +116,7 @@ static void update_events(void)
break;
case EVENT_TYPE_RELAY:
#if CONFIG_RELAY == ENABLED
relay.toggle();
#endif
break;
}

2
ArduPlane/system.pde

@ -197,9 +197,7 @@ static void init_ardupilot() @@ -197,9 +197,7 @@ static void init_ardupilot()
pinMode(C_LED_PIN, OUTPUT); // GPS status LED
pinMode(A_LED_PIN, OUTPUT); // GPS status LED
pinMode(B_LED_PIN, OUTPUT); // GPS status LED
#if CONFIG_RELAY == ENABLED
relay.init();
#endif
#if FENCE_TRIGGERED_PIN > 0
pinMode(FENCE_TRIGGERED_PIN, OUTPUT);

6
ArduPlane/test.pde

@ -14,9 +14,7 @@ static int8_t test_adc(uint8_t argc, const Menu::arg *argv); @@ -14,9 +14,7 @@ static int8_t test_adc(uint8_t argc, const Menu::arg *argv);
#endif
static int8_t test_ins(uint8_t argc, const Menu::arg *argv);
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
#if CONFIG_RELAY == ENABLED
static int8_t test_relay(uint8_t argc, const Menu::arg *argv);
#endif
static int8_t test_wp(uint8_t argc, const Menu::arg *argv);
static int8_t test_airspeed(uint8_t argc, const Menu::arg *argv);
static int8_t test_pressure(uint8_t argc, const Menu::arg *argv);
@ -37,9 +35,7 @@ static const struct Menu::command test_menu_commands[] PROGMEM = { @@ -37,9 +35,7 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
{"passthru", test_passthru},
{"failsafe", test_failsafe},
{"battery", test_battery},
#if CONFIG_RELAY == ENABLED
{"relay", test_relay},
#endif
{"waypoints", test_wp},
{"xbee", test_xbee},
{"eedump", test_eedump},
@ -284,7 +280,6 @@ test_battery(uint8_t argc, const Menu::arg *argv) @@ -284,7 +280,6 @@ test_battery(uint8_t argc, const Menu::arg *argv)
}
#if CONFIG_RELAY == ENABLED
static int8_t
test_relay(uint8_t argc, const Menu::arg *argv)
{
@ -307,7 +302,6 @@ test_relay(uint8_t argc, const Menu::arg *argv) @@ -307,7 +302,6 @@ test_relay(uint8_t argc, const Menu::arg *argv)
}
}
}
#endif
static int8_t
test_wp(uint8_t argc, const Menu::arg *argv)

Loading…
Cancel
Save