AntennaTracker: removed old PROXY_MODE parameter

this should not be needed any more
This commit is contained in:
Andrew Tridgell 2014-12-10 14:35:39 +11:00 committed by Randy Mackay
parent c94e934fdf
commit 0d2308f754
5 changed files with 2 additions and 30 deletions

View File

@ -173,10 +173,6 @@ static RC_Channel channel_pitch(CH_PITCH);
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;

View File

@ -742,14 +742,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
@ -820,10 +812,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)

View File

@ -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,
@ -126,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;

View File

@ -122,13 +122,6 @@ 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.
// @Values: 0:Off,1:On
// @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

View File

@ -42,11 +42,7 @@ static void init_tracker()
// we have a 2nd serial port for telemetry
hal.uartC->begin(map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
if (g.proxy_mode == true) {
proxy_vehicle.setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
} else {
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
}
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
mavlink_system.sysid = g.sysid_this_mav;