1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-04-08 00:53:48 +02:00

Added configuration of COM ports on PipX.

This commit is contained in:
Brian Webb 2012-05-12 13:16:36 -07:00
parent dd02873908
commit ec67742ff6
7 changed files with 259 additions and 96 deletions

View File

@ -80,10 +80,7 @@ typedef struct {
xTaskHandle sendPacketTaskHandle; xTaskHandle sendPacketTaskHandle;
xTaskHandle sendDataTaskHandle; xTaskHandle sendDataTaskHandle;
xTaskHandle radioStatusTaskHandle; xTaskHandle radioStatusTaskHandle;
xTaskHandle transparentCommTaskHandle;
// The com ports
uint32_t com_port;
uint32_t radio_port;
// The UAVTalk connection on the com side. // The UAVTalk connection on the com side.
UAVTalkConnection inUAVTalkCon; UAVTalkConnection inUAVTalkCon;
@ -132,6 +129,7 @@ static void comUAVTalkTask(void *parameters);
static void radioReceiveTask(void *parameters); static void radioReceiveTask(void *parameters);
static void sendPacketTask(void *parameters); static void sendPacketTask(void *parameters);
static void sendDataTask(void *parameters); static void sendDataTask(void *parameters);
static void transparentCommTask(void * parameters);
static void radioStatusTask(void *parameters); static void radioStatusTask(void *parameters);
static int32_t transmitData(uint8_t * data, int32_t length); static int32_t transmitData(uint8_t * data, int32_t length);
static int32_t transmitPacket(PHPacketHandle packet); static int32_t transmitPacket(PHPacketHandle packet);
@ -141,6 +139,7 @@ static void PPMHandler(uint16_t *channels);
static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length); static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length);
static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms); static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms);
static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port); static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port);
static void updateSettings();
// **************** // ****************
// Private variables // Private variables
@ -157,12 +156,16 @@ static int32_t RadioComBridgeStart(void)
if(data) { if(data) {
// Start the tasks // Start the tasks
xTaskCreate(comUAVTalkTask, (signed char *)"ComUAVTalk", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY + 2, &(data->comUAVTalkTaskHandle)); xTaskCreate(comUAVTalkTask, (signed char *)"ComUAVTalk", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY + 2, &(data->comUAVTalkTaskHandle));
if(PIOS_COM_TRANS_COM)
xTaskCreate(transparentCommTask, (signed char *)"transparentComm", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY + 2, &(data->transparentCommTaskHandle));
xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->radioReceiveTaskHandle)); xTaskCreate(radioReceiveTask, (signed char *)"RadioReceive", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->radioReceiveTaskHandle));
xTaskCreate(sendPacketTask, (signed char *)"SendPacketTask", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->sendPacketTaskHandle)); xTaskCreate(sendPacketTask, (signed char *)"SendPacketTask", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->sendPacketTaskHandle));
xTaskCreate(sendDataTask, (signed char *)"SendDataTask", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->sendDataTaskHandle)); xTaskCreate(sendDataTask, (signed char *)"SendDataTask", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->sendDataTaskHandle));
xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle)); xTaskCreate(radioStatusTask, (signed char *)"RadioStatus", STACK_SIZE_BYTES/2, NULL, TASK_PRIORITY, &(data->radioStatusTaskHandle));
#ifdef PIOS_INCLUDE_WDG #ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_COMUAVTALK); PIOS_WDG_RegisterFlag(PIOS_WDG_COMUAVTALK);
if(PIOS_COM_TRANS_COM)
PIOS_WDG_RegisterFlag(PIOS_WDG_TRANSCOMM);
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE); PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE);
PIOS_WDG_RegisterFlag(PIOS_WDG_SENDPACKET); PIOS_WDG_RegisterFlag(PIOS_WDG_SENDPACKET);
PIOS_WDG_RegisterFlag(PIOS_WDG_SENDDATA); PIOS_WDG_RegisterFlag(PIOS_WDG_SENDDATA);
@ -190,14 +193,7 @@ static int32_t RadioComBridgeInitialize(void)
GCSReceiverInitialize(); GCSReceiverInitialize();
PipXStatusInitialize(); PipXStatusInitialize();
ObjectPersistenceInitialize(); ObjectPersistenceInitialize();
updateSettings();
// Get the settings.
PipXSettingsData pipxSettings;
PipXSettingsGet(&pipxSettings);
// TODO: Get from settings object
data->com_port = PIOS_COM_BRIDGE_COM;
data->radio_port = PIOS_COM_BRIDGE_RADIO;
// Initialise UAVTalk // Initialise UAVTalk
data->inUAVTalkCon = UAVTalkInitialize(0); data->inUAVTalkCon = UAVTalkInitialize(0);
@ -207,10 +203,6 @@ static int32_t RadioComBridgeInitialize(void)
data->sendPacketQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle)); data->sendPacketQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(PHPacketHandle));
data->objEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent)); data->objEventQueue = xQueueCreate(PACKET_QUEUE_SIZE, sizeof(UAVObjEvent));
// Initialize the destination ID
data->destination_id = pipxSettings.PairID ? pipxSettings.PairID : 0xffffffff;
DEBUG_PRINTF(2, "PairID: %x\n\r", data->destination_id);
// Initialize the statistics. // Initialize the statistics.
data->radioTxErrors = 0; data->radioTxErrors = 0;
data->radioTxRetries = 0; data->radioTxRetries = 0;
@ -256,7 +248,7 @@ static void comUAVTalkTask(void *parameters)
PHPacketHandle p = NULL; PHPacketHandle p = NULL;
// Create the buffered reader. // Create the buffered reader.
BufferedReadHandle f = BufferedReadInit(data->com_port, TEMP_BUFFER_SIZE); BufferedReadHandle f = BufferedReadInit(PIOS_COM_UAVTALK, TEMP_BUFFER_SIZE);
while (1) { while (1) {
@ -265,13 +257,19 @@ static void comUAVTalkTask(void *parameters)
PIOS_WDG_UpdateFlag(PIOS_WDG_COMUAVTALK); PIOS_WDG_UpdateFlag(PIOS_WDG_COMUAVTALK);
#endif /* PIOS_INCLUDE_WDG */ #endif /* PIOS_INCLUDE_WDG */
// Receive from USB HID if available, otherwise UAVTalk com if it's available.
#if defined(PIOS_INCLUDE_USB) #if defined(PIOS_INCLUDE_USB)
// Determine input port (USB takes priority over telemetry port) // Determine input port (USB takes priority over telemetry port)
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID)
BufferedReadSetCom(f, PIOS_COM_TELEM_USB); BufferedReadSetCom(f, PIOS_COM_USB_HID);
else else
#endif /* PIOS_INCLUDE_USB */ #endif /* PIOS_INCLUDE_USB */
BufferedReadSetCom(f, data->com_port); {
if (PIOS_COM_UAVTALK)
BufferedReadSetCom(f, PIOS_COM_UAVTALK);
else
vTaskDelay(5);
}
// Read the next byte // Read the next byte
uint8_t rx_byte; uint8_t rx_byte;
@ -295,7 +293,7 @@ static void comUAVTalkTask(void *parameters)
if (p == NULL) if (p == NULL)
{ {
DEBUG_PRINTF(2, "Packet dropped!\n\r"); DEBUG_PRINTF(2, "Packet dropped!\n\r");
return; continue;
} }
// Initialize the packet. // Initialize the packet.
@ -477,7 +475,7 @@ static void radioReceiveTask(void *parameters)
} }
// Receive data from the radio port // Receive data from the radio port
rx_bytes = PIOS_COM_ReceiveBuffer(data->radio_port, (uint8_t*)p, PIOS_PH_MAX_PACKET, MAX_PORT_DELAY); rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, (uint8_t*)p, PIOS_PH_MAX_PACKET, MAX_PORT_DELAY);
if(rx_bytes == 0) if(rx_bytes == 0)
continue; continue;
data->rxBytes += rx_bytes; data->rxBytes += rx_bytes;
@ -562,44 +560,51 @@ static void sendDataTask(void *parameters)
} }
} }
#ifdef NEVER
/** /**
* The com to radio bridge task. * The com to radio bridge task.
*/ */
static void com2RadioBridgeTask(void * parameters) static void transparentCommTask(void * parameters)
{ {
uint32_t rx_bytes = 0;
portTickType packet_start_time = 0; portTickType packet_start_time = 0;
uint32_t timeout = 250; uint32_t timeout = 250;
uint32_t inputPort; PHPacketHandle p = NULL;
/* Handle usart/usb -> radio direction */ /* Handle usart/usb -> radio direction */
while (1) { while (1) {
#if defined(PIOS_INCLUDE_USB)
// Determine input port (USB takes priority over telemetry port)
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB)
inputPort = PIOS_COM_TELEM_USB;
else
#endif /* PIOS_INCLUDE_USB */
inputPort = data->com_port;
#ifdef PIOS_INCLUDE_WDG #ifdef PIOS_INCLUDE_WDG
// Update the watchdog timer. // Update the watchdog timer.
PIOS_WDG_UpdateFlag(PIOS_WDG_COMRADIO); PIOS_WDG_UpdateFlag(PIOS_WDG_TRANSCOMM);
#endif /* PIOS_INCLUDE_WDG */ #endif /* PIOS_INCLUDE_WDG */
// Receive data from the com port // Get a TX packet from the packet handler if required.
uint32_t cur_rx_bytes = PIOS_COM_ReceiveBuffer(inputPort, data->com2radio_buf + if (p == NULL)
rx_bytes, BRIDGE_BUF_LEN - rx_bytes, timeout); {
p = PHGetTXPacket(pios_packet_handler);
// Pass the new data through UAVTalk // No packets available?
for (uint8_t i = 0; i < cur_rx_bytes; i++) if (p == NULL)
UAVTalkProcessInputStreamQuiet(data->inUAVTalkCon, *(data->com2radio_buf + i + rx_bytes)); {
// Wait a bit for a packet to come available.
vTaskDelay(5);
continue;
}
// Initialize the packet.
p->header.destination_id = data->destination_id;
p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
//p->header.type = PACKET_TYPE_ACKED_DATA;
p->header.type = PACKET_TYPE_DATA;
p->header.data_size = 0;
}
// Receive data from the com port
uint32_t cur_rx_bytes = PIOS_COM_ReceiveBuffer(PIOS_COM_TRANS_COM, p->data + p->header.data_size,
PH_MAX_DATA - p->header.data_size, timeout);
// Do we have an data to send? // Do we have an data to send?
rx_bytes += cur_rx_bytes; p->header.data_size += cur_rx_bytes;
if (rx_bytes > 0) { if (p->header.data_size > 0) {
// Check how long since last update // Check how long since last update
portTickType cur_sys_time = xTaskGetTickCount(); portTickType cur_sys_time = xTaskGetTickCount();
@ -620,36 +625,22 @@ static void com2RadioBridgeTask(void * parameters)
} }
// Also send the packet if the size is over the minimum. // Also send the packet if the size is over the minimum.
send_packet |= (rx_bytes > data->min_packet_size); send_packet |= (p->header.data_size > data->min_packet_size);
// Should we send this packet? // Should we send this packet?
if (send_packet) if (send_packet)
{ {
// Get a TX packet from the packet handler
PHPacketHandle p = PHGetTXPacket(pios_packet_handler);
// Initialize the packet.
//p->header.type = PACKET_TYPE_ACKED_DATA;
p->header.destination_id = data->destination_id;
p->header.source_id = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
p->header.type = PACKET_TYPE_DATA;
p->header.data_size = rx_bytes;
// Copy the data into the packet.
memcpy(p->data, data->com2radio_buf, rx_bytes);
// Transmit the packet // Transmit the packet
PHTransmitPacket(pios_packet_handler, p); PHTransmitPacket(pios_packet_handler, p);
// Reset the timeout // Reset the timeout
timeout = 500; timeout = 500;
rx_bytes = 0; p = NULL;
packet_start_time = 0; packet_start_time = 0;
} }
} }
} }
} }
#endif
/** /**
* The stats update task. * The stats update task.
@ -717,11 +708,11 @@ static void radioStatusTask(void *parameters)
*/ */
static int32_t transmitData(uint8_t *buf, int32_t length) static int32_t transmitData(uint8_t *buf, int32_t length)
{ {
uint32_t outputPort = data->com_port; uint32_t outputPort = PIOS_COM_UAVTALK;
#if defined(PIOS_INCLUDE_USB) #if defined(PIOS_INCLUDE_USB)
// Determine output port (USB takes priority over telemetry port) // Determine output port (USB takes priority over telemetry port)
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID)
outputPort = PIOS_COM_TELEM_USB; outputPort = PIOS_COM_USB_HID;
#endif /* PIOS_INCLUDE_USB */ #endif /* PIOS_INCLUDE_USB */
return PIOS_COM_SendBuffer(outputPort, buf, length); return PIOS_COM_SendBuffer(outputPort, buf, length);
} }
@ -735,7 +726,7 @@ static int32_t transmitData(uint8_t *buf, int32_t length)
*/ */
static int32_t transmitPacket(PHPacketHandle p) static int32_t transmitPacket(PHPacketHandle p)
{ {
return PIOS_COM_SendBuffer(data->radio_port, (uint8_t*)p, PH_PACKET_SIZE(p)); return PIOS_COM_SendBuffer(PIOS_COM_RADIO, (uint8_t*)p, PH_PACKET_SIZE(p));
} }
/** /**
@ -745,12 +736,20 @@ static int32_t transmitPacket(PHPacketHandle p)
*/ */
static void receiveData(uint8_t *buf, uint8_t len) static void receiveData(uint8_t *buf, uint8_t len)
{ {
uint32_t outputPort = data->com_port; // Packet data should to to transparent com if it's configured,
// USB HID if it's connected, otherwise, UAVTalk com if it's configured.
uint32_t outputPort = PIOS_COM_TRANS_COM;
if (!outputPort)
{
outputPort = PIOS_COM_UAVTALK;
#if defined(PIOS_INCLUDE_USB) #if defined(PIOS_INCLUDE_USB)
// Determine output port (USB takes priority over telemetry port) // Determine output port (USB takes priority over telemetry port)
if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) if (PIOS_USB_CheckAvailable(0) && PIOS_COM_USB_HID)
outputPort = PIOS_COM_TELEM_USB; outputPort = PIOS_COM_USB_HID;
#endif /* PIOS_INCLUDE_USB */ #endif /* PIOS_INCLUDE_USB */
}
if (!outputPort)
return;
// Send the received data to the com port // Send the received data to the com port
if (PIOS_COM_SendBuffer(outputPort, buf, len) != len) if (PIOS_COM_SendBuffer(outputPort, buf, len) != len)
@ -867,3 +866,98 @@ static void BufferedReadSetCom(BufferedReadHandle h, uint32_t com_port)
{ {
h->com_port = com_port; h->com_port = com_port;
} }
/**
* Update the telemetry settings, called on startup.
* FIXME: This should be in the TelemetrySettings object. But objects
* have too much overhead yet. Also the telemetry has no any specific
* settings, etc. Thus the HwSettings object which contains the
* telemetry port speed is used for now.
*/
static void updateSettings()
{
// Get the settings.
PipXSettingsData pipxSettings;
PipXSettingsGet(&pipxSettings);
// Initialize the destination ID
data->destination_id = pipxSettings.PairID ? pipxSettings.PairID : 0xffffffff;
DEBUG_PRINTF(2, "PairID: %x\n\r", data->destination_id);
if (PIOS_COM_TELEMETRY) {
switch (pipxSettings.TelemetrySpeed) {
case PIPXSETTINGS_TELEMETRYSPEED_2400:
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 2400);
break;
case PIPXSETTINGS_TELEMETRYSPEED_4800:
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 4800);
break;
case PIPXSETTINGS_TELEMETRYSPEED_9600:
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 9600);
break;
case PIPXSETTINGS_TELEMETRYSPEED_19200:
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 19200);
break;
case PIPXSETTINGS_TELEMETRYSPEED_38400:
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 38400);
break;
case PIPXSETTINGS_TELEMETRYSPEED_57600:
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 57600);
break;
case PIPXSETTINGS_TELEMETRYSPEED_115200:
PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, 115200);
break;
}
}
if (PIOS_COM_FLEXI) {
switch (pipxSettings.FlexiSpeed) {
case PIPXSETTINGS_TELEMETRYSPEED_2400:
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 2400);
break;
case PIPXSETTINGS_TELEMETRYSPEED_4800:
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 4800);
break;
case PIPXSETTINGS_TELEMETRYSPEED_9600:
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 9600);
break;
case PIPXSETTINGS_TELEMETRYSPEED_19200:
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 19200);
break;
case PIPXSETTINGS_TELEMETRYSPEED_38400:
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 38400);
break;
case PIPXSETTINGS_TELEMETRYSPEED_57600:
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 57600);
break;
case PIPXSETTINGS_TELEMETRYSPEED_115200:
PIOS_COM_ChangeBaud(PIOS_COM_FLEXI, 115200);
break;
}
}
if (PIOS_COM_VCP) {
switch (pipxSettings.VCPSpeed) {
case PIPXSETTINGS_TELEMETRYSPEED_2400:
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 2400);
break;
case PIPXSETTINGS_TELEMETRYSPEED_4800:
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 4800);
break;
case PIPXSETTINGS_TELEMETRYSPEED_9600:
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 9600);
break;
case PIPXSETTINGS_TELEMETRYSPEED_19200:
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 19200);
break;
case PIPXSETTINGS_TELEMETRYSPEED_38400:
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 38400);
break;
case PIPXSETTINGS_TELEMETRYSPEED_57600:
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 57600);
break;
case PIPXSETTINGS_TELEMETRYSPEED_115200:
PIOS_COM_ChangeBaud(PIOS_COM_VCP, 115200);
break;
}
}
}

View File

@ -75,6 +75,7 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
#define PIOS_WDG_RADIORECEIVE 0x0002 #define PIOS_WDG_RADIORECEIVE 0x0002
#define PIOS_WDG_SENDPACKET 0x0004 #define PIOS_WDG_SENDPACKET 0x0004
#define PIOS_WDG_SENDDATA 0x0008 #define PIOS_WDG_SENDDATA 0x0008
#define PIOS_WDG_TRANSCOMM 0x0010
//------------------------ //------------------------
// TELEMETRY // TELEMETRY
@ -150,23 +151,26 @@ extern uint32_t pios_spi_port_id;
//------------------------- //-------------------------
#define PIOS_COM_MAX_DEVS 5 #define PIOS_COM_MAX_DEVS 5
extern uint32_t pios_com_telem_usb_id; extern uint32_t pios_com_usb_hid_id;
extern uint32_t pios_com_vcp_usb_id; extern uint32_t pios_com_telemetry_id;
extern uint32_t pios_com_usart1_id; extern uint32_t pios_com_flexi_id;
extern uint32_t pios_com_usart3_id; extern uint32_t pios_com_vcp_id;
extern uint32_t pios_com_uavtalk_com_id;
extern uint32_t pios_com_trans_com_id;
extern uint32_t pios_com_debug_id;
extern uint32_t pios_com_rfm22b_id; extern uint32_t pios_com_rfm22b_id;
#define PIOS_COM_TELEM_SERIAL (pios_com_usart1_id) #define PIOS_COM_USB_HID (pios_com_usb_hid_id)
#define PIOS_COM_FLEXI (pios_com_usart3_id) #define PIOS_COM_TELEMETRY (pios_com_telemetry_id)
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) #define PIOS_COM_FLEXI (pios_com_flexi_id)
#define PIOS_COM_VCP_USB (pios_com_vcp_usb_id) #define PIOS_COM_VCP (pios_com_vcp_id)
#define PIOS_COM_RFM22B_RF (pios_com_rfm22b_id) #define PIOS_COM_UAVTALK (pios_com_uavtalk_com_id)
#define PIOS_COM_BRIDGE_RADIO PIOS_COM_RFM22B_RF #define PIOS_COM_TRANS_COM (pios_com_trans_com_id)
#define PIOS_COM_DEBUG PIOS_COM_FLEXI #define PIOS_COM_DEBUG (pios_com_debug_id)
#define PIOS_COM_BRIDGE_COM PIOS_COM_TELEM_SERIAL #define PIOS_COM_RADIO (pios_com_rfm22b_id)
#define DEBUG_LEVEL 2 #define DEBUG_LEVEL 2
#if DEBUG_LEVEL > 0 #if DEBUG_LEVEL > 0
#define DEBUG_PRINTF(level, ...) if(level <= DEBUG_LEVEL) { PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__); } #define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && PIOS_COM_DEBUG > 0) { PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__); }}
#else #else
#define DEBUG_PRINTF(...) #define DEBUG_PRINTF(...)
#endif #endif

View File

@ -48,12 +48,15 @@
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 192 #define PIOS_COM_RFM22B_RF_RX_BUF_LEN 192
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 192 #define PIOS_COM_RFM22B_RF_TX_BUF_LEN 192
uint32_t pios_com_telem_usb_id; uint32_t pios_com_usb_hid_id = 0;
uint32_t pios_com_vcp_usb_id; uint32_t pios_com_telemetry_id;
uint32_t pios_com_usart1_id; uint32_t pios_com_flexi_id;
uint32_t pios_com_usart3_id; uint32_t pios_com_vcp_id;
uint32_t pios_com_rfm22b_id; uint32_t pios_com_uavtalk_com_id = 0;
uint32_t pios_rfm22b_id; uint32_t pios_com_trans_com_id = 0;
uint32_t pios_com_debug_id = 0;
uint32_t pios_com_rfm22b_id = 0;
uint32_t pios_rfm22b_id = 0;
/** /**
* PIOS_Board_Init() * PIOS_Board_Init()
@ -136,6 +139,10 @@ void PIOS_Board_Init(void) {
#if defined(PIOS_INCLUDE_USB_CDC) #if defined(PIOS_INCLUDE_USB_CDC)
#if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_COM)
switch (pipxSettings.VCPConfig)
{
case PIPXSETTINGS_VCPCONFIG_SERIAL:
case PIPXSETTINGS_VCPCONFIG_DEBUG:
{ {
uint32_t pios_usb_cdc_id; uint32_t pios_usb_cdc_id;
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
@ -145,11 +152,27 @@ void PIOS_Board_Init(void) {
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_VCP_USB_TX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_VCP_USB_TX_BUF_LEN);
PIOS_Assert(rx_buffer); PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_vcp_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
rx_buffer, PIOS_COM_VCP_USB_RX_BUF_LEN, rx_buffer, PIOS_COM_VCP_USB_RX_BUF_LEN,
tx_buffer, PIOS_COM_VCP_USB_TX_BUF_LEN)) { tx_buffer, PIOS_COM_VCP_USB_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
switch (pipxSettings.TelemetryConfig)
{
case PIPXSETTINGS_VCPCONFIG_SERIAL:
pios_com_trans_com_id = pios_com_vcp_id;
break;
case PIPXSETTINGS_VCPCONFIG_UAVTALK:
pios_com_uavtalk_com_id = pios_com_vcp_id;
break;
case PIPXSETTINGS_VCPCONFIG_DEBUG:
pios_com_debug_id = pios_com_vcp_id;
break;
}
break;
}
case PIPXSETTINGS_VCPCONFIG_DISABLED:
break;
} }
#endif /* PIOS_INCLUDE_COM */ #endif /* PIOS_INCLUDE_COM */
@ -168,7 +191,7 @@ void PIOS_Board_Init(void) {
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
PIOS_Assert(rx_buffer); PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, if (PIOS_COM_Init(&pios_com_usb_hid_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
@ -186,27 +209,38 @@ void PIOS_Board_Init(void) {
case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL: case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL:
case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK: case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK:
case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG: case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG:
case PIPXSETTINGS_TELEMETRYCONFIG_DISABLED:
{ {
uint32_t pios_usart1_id; uint32_t pios_usart1_id;
if (PIOS_USART_Init(&pios_usart1_id, &pios_usart_serial_cfg)) { if (PIOS_USART_Init(&pios_usart1_id, &pios_usart_serial_cfg)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_RX_BUF_LEN); uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_RX_BUF_LEN);
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_TX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_SERIAL_TX_BUF_LEN);
PIOS_Assert(rx_buffer); PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_usart1_id, &pios_usart_com_driver, pios_usart1_id, if (PIOS_COM_Init(&pios_com_telemetry_id, &pios_usart_com_driver, pios_usart1_id,
rx_buffer, PIOS_COM_SERIAL_RX_BUF_LEN, rx_buffer, PIOS_COM_SERIAL_RX_BUF_LEN,
tx_buffer, PIOS_COM_SERIAL_TX_BUF_LEN)) { tx_buffer, PIOS_COM_SERIAL_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
switch (pipxSettings.TelemetryConfig)
{
case PIPXSETTINGS_TELEMETRYCONFIG_SERIAL:
pios_com_trans_com_id = pios_com_telemetry_id;
break;
case PIPXSETTINGS_TELEMETRYCONFIG_UAVTALK:
pios_com_uavtalk_com_id = pios_com_telemetry_id;
break;
case PIPXSETTINGS_TELEMETRYCONFIG_DEBUG:
pios_com_debug_id = pios_com_telemetry_id;
break;
}
break; break;
} }
case PIPXSETTINGS_TELEMETRYCONFIG_PPM_IN: case PIPXSETTINGS_TELEMETRYCONFIG_PPM_IN:
case PIPXSETTINGS_TELEMETRYCONFIG_PPM_OUT: case PIPXSETTINGS_TELEMETRYCONFIG_PPM_OUT:
case PIPXSETTINGS_TELEMETRYCONFIG_RSSI: case PIPXSETTINGS_TELEMETRYCONFIG_RSSI:
case PIPXSETTINGS_TELEMETRYCONFIG_DISABLED:
break; break;
} }
@ -225,11 +259,23 @@ void PIOS_Board_Init(void) {
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_FLEXI_TX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_FLEXI_TX_BUF_LEN);
PIOS_Assert(rx_buffer); PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer); PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_usart3_id, &pios_usart_com_driver, pios_usart3_id, if (PIOS_COM_Init(&pios_com_flexi_id, &pios_usart_com_driver, pios_usart3_id,
rx_buffer, PIOS_COM_FLEXI_RX_BUF_LEN, rx_buffer, PIOS_COM_FLEXI_RX_BUF_LEN,
tx_buffer, PIOS_COM_FLEXI_TX_BUF_LEN)) { tx_buffer, PIOS_COM_FLEXI_TX_BUF_LEN)) {
PIOS_Assert(0); PIOS_Assert(0);
} }
switch (pipxSettings.FlexiConfig)
{
case PIPXSETTINGS_FLEXICONFIG_SERIAL:
pios_com_trans_com_id = pios_com_flexi_id;
break;
case PIPXSETTINGS_FLEXICONFIG_UAVTALK:
pios_com_uavtalk_com_id = pios_com_flexi_id;
break;
case PIPXSETTINGS_FLEXICONFIG_DEBUG:
pios_com_debug_id = pios_com_flexi_id;
break;
}
break; break;
} }
case PIPXSETTINGS_FLEXICONFIG_PPM_IN: case PIPXSETTINGS_FLEXICONFIG_PPM_IN:

View File

@ -81,6 +81,10 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
addUAVObjectToWidgetRelation("PipXStatus", "RXRate", m_pipx->RXRate); addUAVObjectToWidgetRelation("PipXStatus", "RXRate", m_pipx->RXRate);
addUAVObjectToWidgetRelation("PipXStatus", "TXRate", m_pipx->TXRate); addUAVObjectToWidgetRelation("PipXStatus", "TXRate", m_pipx->TXRate);
// Create the timer that is used to timeout the connection to the PipX.
timeOut = new QTimer(this);
connect(timeOut, SIGNAL(timeout()),this,SLOT(disconnected()));
// Request and update of the setting object. // Request and update of the setting object.
settingsUpdated = false; settingsUpdated = false;
pipxSettingsObj->requestUpdate(); pipxSettingsObj->requestUpdate();
@ -125,7 +129,11 @@ void ConfigPipXtremeWidget::saveSettings()
/*! /*!
\brief Called by updates to @PipXStatus \brief Called by updates to @PipXStatus
*/ */
void ConfigPipXtremeWidget::updateStatus(UAVObject *object) { void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
{
// Restart the disconnection timer.
timeOut->start(5000);
// Request and update of the setting object if we haven't received it yet. // Request and update of the setting object if we haven't received it yet.
if (!settingsUpdated) if (!settingsUpdated)
@ -228,7 +236,8 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object) {
/*! /*!
\brief Called by updates to @PipXSettings \brief Called by updates to @PipXSettings
*/ */
void ConfigPipXtremeWidget::updateSettings(UAVObject *object) { void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
{
settingsUpdated = true; settingsUpdated = true;
enableControls(true); enableControls(true);
@ -238,6 +247,12 @@ void ConfigPipXtremeWidget::updateSettings(UAVObject *object) {
pairID = pipxSettingsData.PairID; pairID = pipxSettingsData.PairID;
} }
void ConfigPipXtremeWidget::disconnected()
{
settingsUpdated = false;
enableControls(false);
}
/** /**
@} @}
@} @}

View File

@ -54,10 +54,14 @@ private:
bool settingsUpdated; bool settingsUpdated;
quint32 pairID; quint32 pairID;
// A timer that timesout the connction to the PipX.
QTimer *timeOut;
private slots: private slots:
void refreshValues(); void refreshValues();
void applySettings(); void applySettings();
void saveSettings(); void saveSettings();
void disconnected();
}; };
#endif // CONFIGTXPIDWIDGET_H #endif // CONFIGTXPIDWIDGET_H

View File

@ -87,7 +87,7 @@ void smartSaveButton::processOperation(QPushButton * button,bool save)
connect(obj,SIGNAL(transactionCompleted(UAVObject*,bool)),this,SLOT(transaction_finished(UAVObject*, bool))); connect(obj,SIGNAL(transactionCompleted(UAVObject*,bool)),this,SLOT(transaction_finished(UAVObject*, bool)));
connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit()));
obj->updated(); obj->updated();
timer.start(2000); timer.start(3000);
//qDebug()<<"begin loop"; //qDebug()<<"begin loop";
loop.exec(); loop.exec();
//qDebug()<<"end loop"; //qDebug()<<"end loop";
@ -113,7 +113,7 @@ void smartSaveButton::processOperation(QPushButton * button,bool save)
connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool)));
connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit()));
utilMngr->saveObjectToSD(obj); utilMngr->saveObjectToSD(obj);
timer.start(2000); timer.start(3000);
loop.exec(); loop.exec();
timer.stop(); timer.stop();
disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool)));

View File

@ -6,7 +6,7 @@
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/> <field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<field name="FlexiConfig" units="function" type="enum" elements="1" options="Disabled,Serial,UAVTalk,PPM_In,PPM_Out,RSSI,Debug" defaultvalue="Disabled"/> <field name="FlexiConfig" units="function" type="enum" elements="1" options="Disabled,Serial,UAVTalk,PPM_In,PPM_Out,RSSI,Debug" defaultvalue="Disabled"/>
<field name="FlexiSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/> <field name="FlexiSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<field name="VCPConfig" units="function" type="enum" elements="1" options="Disabled,Serial,UAVTalk" defaultvalue="Disabled"/> <field name="VCPConfig" units="function" type="enum" elements="1" options="Disabled,Serial,UAVTalk,Debug" defaultvalue="Disabled"/>
<field name="VCPSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/> <field name="VCPSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
<field name="RFSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="115200"/> <field name="RFSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="115200"/>
<field name="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="100"/> <field name="MaxRFPower" units="mW" type="enum" elements="1" options="1.25,1.6,3.16,6.3,12.6,25,50,100" defaultvalue="100"/>