1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-17 02:52:12 +01:00

Merge remote-tracking branch 'op-public/next' into revo-next

Conflicts:
	Makefile
	flight/PiOS/Boards/STM32F4xx_Revolution.h
	flight/Revolution/System/inc/pios_config.h
	package/Makefile

Fixed CRLF line end clobbering in:
	flight/Bootloaders/Revolution/inc/pios_config.h
	flight/Modules/OveroSync/inc/overosync.h
	flight/Modules/Sensors/inc/sensors.h
	flight/PiOS.posix/posix/Libraries/FreeRTOS/Source/tasks.c
	flight/PiOS/Boards/STM32F4xx_Revolution.h
	flight/PiOS/Common/pios_usb_util.c
	flight/PiOS/STM32F4xx/pios_iap.c
	flight/PiOS/inc/pios_rfm22b_priv.h
	flight/PiOS/inc/pios_usb_util.h
This commit is contained in:
Stacey Sheldon 2012-06-10 19:01:11 -04:00
commit c73cffce59
85 changed files with 6025 additions and 2304 deletions

View File

@ -1,5 +1,12 @@
Short summary of changes. For a complete list see the git log.
2012-06-04
AeroSimRC support merged into next
2012-05-26
VirtualFlybar which allows a more aggressive flight mode than rate mode
support. Also PiroCompensation added.
2012-05-26
Revert some UI changes that didn't work consistently between OSX and Windows.

View File

@ -70,14 +70,13 @@ uint8_t processRX();
void jump_to_app();
int main() {
PIOS_SYS_Init();
if (BSL_HOLD_STATE == 0)
USB_connected = TRUE;
PIOS_SYS_Init();
PIOS_Board_Init();
PIOS_IAP_Init();
USB_connected = PIOS_USB_CableConnected(0);
if (PIOS_IAP_CheckRequest() == TRUE) {
PIOS_Board_Init();
PIOS_DELAY_WaitmS(1000);
User_DFU_request = TRUE;
PIOS_IAP_ClearRequest();

View File

@ -122,6 +122,7 @@ static const struct flashfs_cfg flashfs_w25x_cfg = {
.obj_table_start = 0x00000010,
.obj_table_end = 0x00001000,
.sector_size = 0x00001000,
.chip_size = 0x00080000,
};
static const struct pios_flash_jedec_cfg flash_w25x_cfg = {
@ -135,6 +136,7 @@ static const struct flashfs_cfg flashfs_m25p_cfg = {
.obj_table_start = 0x00000010,
.obj_table_end = 0x00010000,
.sector_size = 0x00010000,
.chip_size = 0x00200000,
};
static const struct pios_flash_jedec_cfg flash_m25p_cfg = {

View File

@ -59,8 +59,6 @@ typedef struct {
uint8_t data_size;
uint8_t tx_seq;
uint8_t rx_seq;
int8_t rssi;
int8_t afc;
} PHPacketHeader;
#define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY)
@ -83,6 +81,7 @@ typedef struct {
uint16_t retries;
uint16_t errors;
uint16_t uavtalk_errors;
uint16_t dropped;
uint16_t resets;
uint8_t ecc[RS_ECC_NPARITY];
} PHStatusPacket, *PHStatusPacketHandle;
@ -93,8 +92,8 @@ typedef struct {
} PacketHandlerConfig;
typedef int32_t (*PHOutputStream)(PHPacketHandle packet);
typedef void (*PHDataHandler)(uint8_t *data, uint8_t len);
typedef void (*PHStatusHandler)(PHStatusPacketHandle s);
typedef void (*PHDataHandler)(uint8_t *data, uint8_t len, int8_t rssi, int8_t afc);
typedef void (*PHStatusHandler)(PHStatusPacketHandle s, int8_t rssi, int8_t afc);
typedef void (*PHPPMHandler)(uint16_t *channels);
typedef uint32_t PHInstHandle;

View File

@ -343,9 +343,9 @@ uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error)
PHPacketDataHandle data = (PHPacketDataHandle)h;
uint16_t len = PHPacketSizeECC(p);
// Add the RSSI and AFC to the packet.
p->header.rssi = *(((int8_t*)p) + len);
p->header.afc = *(((int8_t*)p) + len + 1);
// Extract the RSSI and AFC.
int8_t rssi = *(((int8_t*)p) + len);
int8_t afc = *(((int8_t*)p) + len + 1);
switch (p->header.type) {
@ -355,7 +355,7 @@ uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error)
// Pass on the channels to the status handler.
if(data->status_handler)
data->status_handler((PHStatusPacketHandle)p);
data->status_handler((PHStatusPacketHandle)p, rssi, afc);
break;
@ -374,7 +374,7 @@ uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error)
// Pass on the data.
if(data->data_handler)
data->data_handler(p->data, p->header.data_size);
data->data_handler(p->data, p->header.data_size, rssi, afc);
}
break;
@ -424,7 +424,7 @@ uint8_t PHReceivePacket(PHInstHandle h, PHPacketHandle p, bool rx_error)
// Pass on the data to the data handler.
if(data->data_handler)
data->data_handler(p->data, p->header.data_size);
data->data_handler(p->data, p->header.data_size, rssi, afc);
break;

View File

@ -234,17 +234,21 @@ static void AttitudeTask(void *parameters)
AccelsData accels;
GyrosData gyros;
int32_t retval;
if(cc3d)
int32_t retval = 0;
if (cc3d)
retval = updateSensorsCC3D(&accels, &gyros);
else
retval = updateSensors(&accels, &gyros);
if(retval != 0)
// Only update attitude when sensor data is good
if (retval != 0)
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
else {
// Only update attitude when sensor data is good
updateAttitude(&accels, &gyros);
// Do not update attitude data in simulation mode
if (!AttitudeActualReadOnly())
updateAttitude(&accels, &gyros);
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
}
}
@ -267,7 +271,11 @@ static int32_t updateSensors(AccelsData * accels, GyrosData * gyros)
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
return -1;
}
// Do not read raw sensor data in simulation mode
if (GyrosReadOnly() || AccelsReadOnly())
return 0;
// No accel data available
if(PIOS_ADXL345_FifoElements() == 0)
return -1;

View File

@ -596,6 +596,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Roll :
0; // this is an invalid mode
;
stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch :
@ -603,6 +604,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Pitch :
0; // this is an invalid mode
stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw :
@ -610,6 +612,7 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Yaw :
0; // this is an invalid mode
stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle;

View File

@ -55,8 +55,8 @@
#define BRIDGE_BUF_LEN 512
#define MAX_RETRIES 2
#define RETRY_TIMEOUT_MS 20
#define STATS_UPDATE_PERIOD_MS 2000
#define RADIOSTATS_UPDATE_PERIOD_MS 1000
#define STATS_UPDATE_PERIOD_MS 500
#define RADIOSTATS_UPDATE_PERIOD_MS 250
#define MAX_LOST_CONTACT_TIME 4
#define PACKET_QUEUE_SIZE 10
#define MAX_PORT_DELAY 200
@ -73,6 +73,7 @@ typedef struct {
uint16_t errors;
uint16_t uavtalk_errors;
uint16_t resets;
uint16_t dropped;
int8_t rssi;
uint8_t lastContact;
} PairStats;
@ -104,6 +105,7 @@ typedef struct {
uint32_t radioRxErrors;
uint32_t UAVTalkErrors;
uint32_t packetErrors;
uint32_t droppedPackets;
uint16_t txBytes;
uint16_t rxBytes;
@ -117,6 +119,9 @@ typedef struct {
// Track other radios that are in range.
PairStats pairStats[PIPXSTATUS_PAIRIDS_NUMELEM];
// The RSSI of the last packet received.
int8_t RSSI;
} RadioComBridgeData;
typedef struct {
@ -139,8 +144,8 @@ static void radioStatusTask(void *parameters);
static void ppmInputTask(void *parameters);
static int32_t transmitData(uint8_t * data, int32_t length);
static int32_t transmitPacket(PHPacketHandle packet);
static void receiveData(uint8_t *buf, uint8_t len);
static void StatusHandler(PHStatusPacketHandle p);
static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc);
static void StatusHandler(PHStatusPacketHandle p, int8_t rssi, int8_t afc);
static void PPMHandler(uint16_t *channels);
static BufferedReadHandle BufferedReadInit(uint32_t com_port, uint16_t buffer_length);
static bool BufferedRead(BufferedReadHandle h, uint8_t *value, uint32_t timeout_ms);
@ -175,7 +180,7 @@ static int32_t RadioComBridgeStart(void)
if(PIOS_COM_TRANS_COM)
PIOS_WDG_RegisterFlag(PIOS_WDG_TRANSCOMM);
PIOS_WDG_RegisterFlag(PIOS_WDG_RADIORECEIVE);
PIOS_WDG_RegisterFlag(PIOS_WDG_SENDPACKET);
//PIOS_WDG_RegisterFlag(PIOS_WDG_SENDPACKET);
//PIOS_WDG_RegisterFlag(PIOS_WDG_SENDDATA);
if(PIOS_PPM_RECEIVER)
PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT);
@ -222,6 +227,7 @@ static int32_t RadioComBridgeInitialize(void)
data->comRxErrors = 0;
data->UAVTalkErrors = 0;
data->packetErrors = 0;
data->RSSI = -127;
// Register the callbacks with the packet handler
PHRegisterOutputStream(pios_packet_handler, transmitPacket);
@ -242,6 +248,7 @@ static int32_t RadioComBridgeInitialize(void)
data->pairStats[i].errors = 0;
data->pairStats[i].uavtalk_errors = 0;
data->pairStats[i].resets = 0;
data->pairStats[i].dropped = 0;
data->pairStats[i].lastContact = 0;
}
// The first slot is reserved for our current pairID
@ -294,7 +301,6 @@ static void comUAVTalkTask(void *parameters)
uint8_t rx_byte;
if(!BufferedRead(f, &rx_byte, MAX_PORT_DELAY))
continue;
data->txBytes++;
// Get a TX packet from the packet handler if required.
if (p == NULL)
@ -311,7 +317,7 @@ static void comUAVTalkTask(void *parameters)
// No packets available?
if (p == NULL)
{
DEBUG_PRINTF(2, "Packet dropped!\n\r");
data->droppedPackets++;
continue;
}
@ -510,7 +516,7 @@ static void radioReceiveTask(void *parameters)
} else
{
data->packetErrors++;
PHReceivePacket(pios_packet_handler, p, false);
PHReceivePacket(pios_packet_handler, p, true);
}
p = NULL;
}
@ -527,7 +533,7 @@ static void sendPacketTask(void *parameters)
while (1) {
#ifdef PIOS_INCLUDE_WDG
// Update the watchdog timer.
PIOS_WDG_UpdateFlag(PIOS_WDG_SENDPACKET);
//PIOS_WDG_UpdateFlag(PIOS_WDG_SENDPACKET);
#endif /* PIOS_INCLUDE_WDG */
// Wait for a packet on the queue.
if (xQueueReceive(data->sendPacketQueue, &p, MAX_PORT_DELAY) == pdTRUE) {
@ -622,6 +628,7 @@ static void transparentCommTask(void * parameters)
// No packets available?
if (p == NULL)
{
data->droppedPackets++;
// Wait a bit for a packet to come available.
vTaskDelay(5);
continue;
@ -696,16 +703,18 @@ static void radioStatusTask(void *parameters)
// Update the status
pipxStatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id);
pipxStatus.RSSI = PIOS_RFM22B_RSSI(pios_rfm22b_id);
pipxStatus.Retries = data->comTxRetries;
pipxStatus.Errors = data->packetErrors;
pipxStatus.UAVTalkErrors = data->UAVTalkErrors;
pipxStatus.Dropped = data->droppedPackets;
pipxStatus.Resets = PIOS_RFM22B_Resets(pios_rfm22b_id);
pipxStatus.TXRate = (uint16_t)((float)(data->txBytes * 1000) / STATS_UPDATE_PERIOD_MS);
data->txBytes = 0;
pipxStatus.RXRate = (uint16_t)((float)(data->rxBytes * 1000) / STATS_UPDATE_PERIOD_MS);
data->rxBytes = 0;
pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_DISCONNECTED;
pipxStatus.RSSI = data->RSSI;
LINK_LED_OFF;
// Update the potential pairing contacts
for (uint8_t i = 0; i < PIPXSTATUS_PAIRIDS_NUMELEM; ++i)
@ -713,14 +722,29 @@ static void radioStatusTask(void *parameters)
pipxStatus.PairIDs[i] = data->pairStats[i].pairID;
pipxStatus.PairSignalStrengths[i] = data->pairStats[i].rssi;
data->pairStats[i].lastContact++;
// Add the paired devices stats to ours.
if(data->pairStats[i].pairID == pairID)
// Remove this device if it's stale.
if(data->pairStats[i].lastContact > MAX_LOST_CONTACT_TIME)
{
data->pairStats[i].pairID = 0;
data->pairStats[i].rssi = -127;
data->pairStats[i].retries = 0;
data->pairStats[i].errors = 0;
data->pairStats[i].uavtalk_errors = 0;
data->pairStats[i].resets = 0;
data->pairStats[i].dropped = 0;
data->pairStats[i].lastContact = 0;
}
// Add the paired devices statistics to ours.
if(pairID && (data->pairStats[i].pairID == pairID) && (data->pairStats[i].rssi > -127))
{
pipxStatus.Retries += data->pairStats[i].retries;
pipxStatus.Errors += data->pairStats[i].errors;
pipxStatus.UAVTalkErrors += data->pairStats[i].uavtalk_errors;
pipxStatus.Dropped += data->pairStats[i].dropped;
pipxStatus.Resets += data->pairStats[i].resets;
pipxStatus.Dropped += data->pairStats[i].dropped;
pipxStatus.LinkState = PIPXSTATUS_LINKSTATE_CONNECTED;
LINK_LED_ON;
}
}
@ -737,10 +761,10 @@ static void radioStatusTask(void *parameters)
status_packet.header.type = PACKET_TYPE_STATUS;
status_packet.header.data_size = PH_STATUS_DATA_SIZE(&status_packet);
status_packet.header.source_id = pipxStatus.DeviceID;
status_packet.header.rssi = pipxStatus.RSSI;
status_packet.retries = data->comTxRetries;
status_packet.errors = data->packetErrors;
status_packet.uavtalk_errors = data->UAVTalkErrors;
status_packet.dropped = data->droppedPackets;
status_packet.resets = PIOS_RFM22B_Resets(pios_rfm22b_id);
PHPacketHandle sph = (PHPacketHandle)&status_packet;
xQueueSend(data->sendPacketQueue, &sph, MAX_PORT_DELAY);
@ -814,6 +838,7 @@ static int32_t transmitData(uint8_t *buf, int32_t length)
*/
static int32_t transmitPacket(PHPacketHandle p)
{
data->txBytes += PH_PACKET_SIZE(p);
return PIOS_COM_SendBuffer(PIOS_COM_RADIO, (uint8_t*)p, PH_PACKET_SIZE(p));
}
@ -822,8 +847,10 @@ static int32_t transmitPacket(PHPacketHandle p)
* \param[in] buf The received data buffer
* \param[in] length Length of buffer
*/
static void receiveData(uint8_t *buf, uint8_t len)
static void receiveData(uint8_t *buf, uint8_t len, int8_t rssi, int8_t afc)
{
data->RSSI = rssi;
// Packet data should go 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;
@ -849,7 +876,7 @@ static void receiveData(uint8_t *buf, uint8_t len)
* Receive a status packet
* \param[in] status The status structure
*/
static void StatusHandler(PHStatusPacketHandle status)
static void StatusHandler(PHStatusPacketHandle status, int8_t rssi, int8_t afc)
{
uint32_t id = status->header.source_id;
bool found = false;
@ -865,29 +892,15 @@ static void StatusHandler(PHStatusPacketHandle status)
// If we have seen it, update the RSSI and reset the last contact couter
if(found)
{
data->pairStats[id_idx].rssi = status->header.rssi;
data->pairStats[id_idx].rssi = rssi;
data->pairStats[id_idx].retries = status->retries;
data->pairStats[id_idx].errors = status->errors;
data->pairStats[id_idx].uavtalk_errors = status->uavtalk_errors;
data->pairStats[id_idx].resets = status->resets;
data->pairStats[id_idx].dropped = status->dropped;
data->pairStats[id_idx].lastContact = 0;
}
// Remove any contacts that we haven't seen for a while.
for (id_idx = 0; id_idx < PIPXSTATUS_PAIRIDS_NUMELEM; ++id_idx)
{
if(data->pairStats[id_idx].lastContact > MAX_LOST_CONTACT_TIME)
{
data->pairStats[id_idx].pairID = 0;
data->pairStats[id_idx].rssi = -127;
data->pairStats[id_idx].retries = 0;
data->pairStats[id_idx].errors = 0;
data->pairStats[id_idx].uavtalk_errors = 0;
data->pairStats[id_idx].resets = 0;
data->pairStats[id_idx].lastContact = 0;
}
}
// If we haven't seen it, find a slot to put it in.
if (!found)
{
@ -908,11 +921,12 @@ static void StatusHandler(PHStatusPacketHandle status)
}
}
data->pairStats[min_idx].pairID = id;
data->pairStats[min_idx].rssi = status->header.rssi;
data->pairStats[min_idx].rssi = rssi;
data->pairStats[min_idx].retries = status->retries;
data->pairStats[min_idx].errors = status->errors;
data->pairStats[min_idx].uavtalk_errors = status->uavtalk_errors;
data->pairStats[min_idx].resets = status->resets;
data->pairStats[min_idx].dropped = status->dropped;
data->pairStats[min_idx].lastContact = 0;
}
}

View File

@ -55,7 +55,7 @@
#define TASK_PRIORITY (tskIDLE_PRIORITY+4)
#define FAILSAFE_TIMEOUT_MS 30
enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_MAX};
enum {PID_RATE_ROLL, PID_RATE_PITCH, PID_RATE_YAW, PID_ROLL, PID_PITCH, PID_YAW, PID_VBAR_ROLL, PID_VBAR_PITCH, PID_VBAR_YAW, PID_MAX};
enum {ROLL,PITCH,YAW,MAX_AXES};
@ -74,21 +74,24 @@ typedef struct {
static xTaskHandle taskHandle;
static StabilizationSettingsData settings;
static xQueueHandle queue;
float dT = 1;
float gyro_alpha = 0;
float gyro_filtered[3] = {0,0,0};
float axis_lock_accum[3] = {0,0,0};
float vbar_sensitivity[3] = {1, 1, 1};
uint8_t max_axis_lock = 0;
uint8_t max_axislock_rate = 0;
float weak_leveling_kp = 0;
uint8_t weak_leveling_max = 0;
bool lowThrottleZeroIntegral;
float vbar_integral[3] = {0, 0, 0};
float vbar_decay = 0.991f;
pid_type pids[PID_MAX];
int8_t vbar_gyros_suppress;
bool vbar_piro_comp = false;
// Private functions
static void stabilizationTask(void* parameters);
static float ApplyPid(pid_type * pid, const float err);
static float ApplyPid(pid_type * pid, const float err, float dT);
static float bound(float val);
static void ZeroPids(void);
static void SettingsUpdatedCb(UAVObjEvent * ev);
@ -154,6 +157,8 @@ static void stabilizationTask(void* parameters)
// Main task loop
ZeroPids();
while(1) {
float dT;
PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION);
// Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe
@ -227,6 +232,7 @@ static void stabilizationTask(void* parameters)
switch(stabDesired.StabilizationMode[i])
{
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR:
rateDesiredAxis[i] = attitudeDesiredAxis[i];
// Zero attitude and axis lock accumulators
@ -251,7 +257,7 @@ static void stabilizationTask(void* parameters)
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i]);
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i], dT);
if(rateDesiredAxis[i] > settings.MaximumRate[i])
rateDesiredAxis[i] = settings.MaximumRate[i];
@ -275,7 +281,7 @@ static void stabilizationTask(void* parameters)
else if(axis_lock_accum[i] < -max_axis_lock)
axis_lock_accum[i] = -max_axis_lock;
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i]);
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i], dT);
}
if(rateDesiredAxis[i] > settings.MaximumRate[i])
@ -287,42 +293,78 @@ static void stabilizationTask(void* parameters)
}
}
// Piro compensation rotates the virtual flybar by yaw step to keep it
// rotated to external world
if (vbar_piro_comp) {
const float F_PI = 3.14159f;
float cy = cosf(gyro_filtered[2] / 180.0f * F_PI * dT);
float sy = sinf(gyro_filtered[2] / 180.0f * F_PI * dT);
float vbar_pitch = cy * vbar_integral[1] - sy * vbar_integral[0];
float vbar_roll = sy * vbar_integral[1] + cy * vbar_integral[0];
vbar_integral[1] = vbar_pitch;
vbar_integral[0] = vbar_roll;
}
uint8_t shouldUpdate = 1;
#if defined(DIAGNOSTICS)
RateDesiredSet(&rateDesired);
#endif
ActuatorDesiredGet(&actuatorDesired);
//Calculate desired command
for(int8_t ct=0; ct< MAX_AXES; ct++)
for(uint32_t i = 0; i < MAX_AXES; i++)
{
switch(stabDesired.StabilizationMode[ct])
switch(stabDesired.StabilizationMode[i])
{
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
{
float command = ApplyPid(&pids[PID_RATE_ROLL + ct], rateDesiredAxis[ct] - gyro_filtered[ct]);
actuatorDesiredAxis[ct] = bound(command);
float command = ApplyPid(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i] - gyro_filtered[i], dT);
actuatorDesiredAxis[i] = bound(command);
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR:
{
// Track the angle of the virtual flybar which includes a slow decay
vbar_integral[i] = vbar_integral[i] * vbar_decay + gyro_filtered[i] * dT;
if (vbar_integral[i] > settings.VbarMaxAngle)
vbar_integral[i] = settings.VbarMaxAngle;
if (-vbar_integral[i] < -settings.VbarMaxAngle)
vbar_integral[i] = -settings.VbarMaxAngle;
// Command signal is composed of stick input added to the gyro and virtual flybar
float gyro_gain = 1.0f;
if (vbar_gyros_suppress > 0) {
gyro_gain = (1.0f - fabs(rateDesiredAxis[i]) * vbar_gyros_suppress / 100.0f);
gyro_gain = (gyro_gain < 0) ? 0 : gyro_gain;
}
float command = rateDesiredAxis[i] * vbar_sensitivity[i] - gyro_gain * (
vbar_integral[i] * pids[PID_VBAR_ROLL + i].i +
gyro_filtered[i] * pids[PID_VBAR_ROLL + i].p);
actuatorDesiredAxis[i] = bound(command);
break;
}
case STABILIZATIONDESIRED_STABILIZATIONMODE_NONE:
switch (ct)
switch (i)
{
case ROLL:
actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]);
actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]);
shouldUpdate = 1;
pids[PID_RATE_ROLL].iAccumulator = 0;
pids[PID_ROLL].iAccumulator = 0;
break;
case PITCH:
actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]);
actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]);
shouldUpdate = 1;
pids[PID_RATE_PITCH].iAccumulator = 0;
pids[PID_PITCH].iAccumulator = 0;
break;
case YAW:
actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]);
actuatorDesiredAxis[i] = bound(attitudeDesiredAxis[i]);
shouldUpdate = 1;
pids[PID_RATE_YAW].iAccumulator = 0;
pids[PID_YAW].iAccumulator = 0;
@ -360,7 +402,7 @@ static void stabilizationTask(void* parameters)
}
}
float ApplyPid(pid_type * pid, const float err)
float ApplyPid(pid_type * pid, const float err, float dT)
{
float diff = (err - pid->lastErr);
pid->lastErr = err;
@ -400,44 +442,60 @@ static float bound(float val)
return val;
}
static void SettingsUpdatedCb(UAVObjEvent * ev)
{
memset(pids,0,sizeof (pid_type) * PID_MAX);
StabilizationSettingsGet(&settings);
// Set the roll rate PID constants
pids[0].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP];
pids[0].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI];
pids[0].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD];
pids[0].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT];
pids[PID_RATE_ROLL].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP];
pids[PID_RATE_ROLL].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI];
pids[PID_RATE_ROLL].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD];
pids[PID_RATE_ROLL].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT];
// Set the pitch rate PID constants
pids[1].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP];
pids[1].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI];
pids[1].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD];
pids[1].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT];
pids[PID_RATE_PITCH].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP];
pids[PID_RATE_PITCH].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI];
pids[PID_RATE_PITCH].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD];
pids[PID_RATE_PITCH].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT];
// Set the yaw rate PID constants
pids[2].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP];
pids[2].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI];
pids[2].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD];
pids[2].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT];
pids[PID_RATE_YAW].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP];
pids[PID_RATE_YAW].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI];
pids[PID_RATE_YAW].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD];
pids[PID_RATE_YAW].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT];
// Set the roll attitude PI constants
pids[3].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP];
pids[3].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI];
pids[3].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT];
pids[PID_ROLL].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP];
pids[PID_ROLL].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI];
pids[PID_ROLL].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT];
// Set the pitch attitude PI constants
pids[4].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP];
pids[4].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI];
pids[4].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT];
pids[PID_PITCH].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP];
pids[PID_PITCH].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI];
pids[PID_PITCH].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT];
// Set the yaw attitude PI constants
pids[5].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP];
pids[5].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI];
pids[5].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT];
pids[PID_YAW].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP];
pids[PID_YAW].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI];
pids[PID_YAW].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT];
// Set the roll attitude PI constants
pids[PID_VBAR_ROLL].p = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KP];
pids[PID_VBAR_ROLL].i = settings.VbarRollPI[STABILIZATIONSETTINGS_VBARROLLPI_KI];
// Set the pitch attitude PI constants
pids[PID_VBAR_PITCH].p = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KP];
pids[PID_VBAR_PITCH].i = settings.VbarPitchPI[STABILIZATIONSETTINGS_VBARPITCHPI_KI];
// Set the yaw attitude PI constants
pids[PID_VBAR_YAW].p = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KP];
pids[PID_VBAR_YAW].i = settings.VbarYawPI[STABILIZATIONSETTINGS_VBARYAWPI_KI];
// Need to store the vbar sensitivity
vbar_sensitivity[0] = settings.VbarSensitivity[0];
vbar_sensitivity[1] = settings.VbarSensitivity[1];
vbar_sensitivity[2] = settings.VbarSensitivity[2];
// Maximum deviation to accumulate for axis lock
max_axis_lock = settings.MaxAxisLock;
@ -460,6 +518,11 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
gyro_alpha = 0; // not trusting this to resolve to 0
else
gyro_alpha = expf(-fakeDt / settings.GyroTau);
// Compute time constant for vbar decay term based on a tau
vbar_decay = expf(-fakeDt / settings.VbarTau);
vbar_gyros_suppress = settings.VbarGyroSuppress;
vbar_piro_comp = settings.VbarPiroComp == STABILIZATIONSETTINGS_VBARPIROCOMP_TRUE;
}

View File

@ -215,7 +215,7 @@ static void objectUpdatedCb(UAVObjEvent * ev)
// Get object data
ObjectPersistenceGet(&objper);
int retval = -1;
int retval = 1;
// Execute action
if (objper.Operation == OBJECTPERSISTENCE_OPERATION_LOAD) {
if (objper.Selection == OBJECTPERSISTENCE_SELECTION_SINGLEOBJECT) {
@ -242,6 +242,13 @@ static void objectUpdatedCb(UAVObjEvent * ev)
}
// Save selected instance
retval = UAVObjSave(obj, objper.InstanceID);
// Not sure why this is needed
vTaskDelay(10);
// Verify saving worked
if (retval == 0)
retval = UAVObjLoad(obj, objper.InstanceID);
} else if (objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLSETTINGS
|| objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) {
retval = UAVObjSaveSettings();
@ -271,9 +278,17 @@ static void objectUpdatedCb(UAVObjEvent * ev)
retval = PIOS_FLASHFS_Format();
#endif
}
if(retval == 0) {
objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
ObjectPersistenceSet(&objper);
switch(retval) {
case 0:
objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED;
ObjectPersistenceSet(&objper);
break;
case -1:
objper.Operation = OBJECTPERSISTENCE_OPERATION_ERROR;
ObjectPersistenceSet(&objper);
break;
default:
break;
}
}
}

View File

@ -215,7 +215,7 @@ extern uint32_t pios_com_telem_usb_id;
//------------------------
#define PIOS_RCVR_MAX_DEVS 3
#define PIOS_RCVR_MAX_CHANNELS 12
#define PIOS_GCSRCVR_TIMEOUT_MS 100
#define PIOS_GCSRCVR_TIMEOUT_MS 100
//-------------------------
// Receiver PPM input

View File

@ -186,6 +186,7 @@ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId)
* @retval -2 No room in object table
* @retval -3 Unable to write entry into object table
* @retval -4 FS not initialized
* @retval -5
*/
int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId)
{
@ -206,6 +207,10 @@ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId)
if((addr + sizeof(header)) > cfg->obj_table_end)
return -2;
// Verify the address is within the chip
if((addr + cfg->sector_size) > cfg->chip_size)
return -5;
if(PIOS_Flash_Jedec_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0)
return -3;

View File

@ -300,8 +300,6 @@ const uint8_t ss_reg_71[] = { 0x2B, 0x23}; // rfm22_modulation_mode_control2
volatile bool initialized = false;
struct pios_rfm22b_dev * rfm22b_dev;
#if defined(RFM22_EXT_INT_USE)
volatile bool exec_using_spi; // set this if you want to access the SPI bus outside of the interrupt
#endif
@ -345,8 +343,8 @@ volatile uint8_t prev_int_status1; // " "
volatile uint8_t prev_int_status2; // " "
volatile uint8_t prev_ezmac_status; // " "
const char *debug_msg = NULL;
const char *error_msg = NULL;
const char *debug_msg = "";
const char *error_msg = "";
static uint32_t debug_val = 0;
#endif
@ -443,7 +441,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, const struct pios_rfm22b_cfg *cfg)
PIOS_DEBUG_Assert(cfg);
// Allocate the device structure.
rfm22b_dev = (struct pios_rfm22b_dev *) PIOS_RFM22B_alloc();
struct pios_rfm22b_dev * rfm22b_dev = (struct pios_rfm22b_dev *) PIOS_RFM22B_alloc();
if (!rfm22b_dev)
return(-1);
@ -559,20 +557,19 @@ static void PIOS_RFM22B_TxStart(uint32_t rfm22b_id, uint16_t tx_bytes_avail)
// Get some data to send
bool need_yield = false;
if(tx_pre_buffer_size== 0)
if(tx_pre_buffer_size == 0)
tx_pre_buffer_size = (rfm22b_dev->tx_out_cb)(rfm22b_dev->tx_out_context, tx_pre_buffer,
TX_BUFFER_SIZE, NULL, &need_yield);
TX_BUFFER_SIZE, NULL, &need_yield);
if(tx_pre_buffer_size > 0)
{
// already have data to be sent
if (tx_data_wr > 0)
return;
// we are currently transmitting or scanning the spectrum
if (rf_mode == TX_DATA_MODE || rf_mode == TX_STREAM_MODE || rf_mode == TX_CARRIER_MODE ||
rf_mode == TX_PN_MODE || rf_mode == RX_SCAN_SPECTRUM)
rf_mode == TX_PN_MODE || rf_mode == RX_SCAN_SPECTRUM)
return;
// is the channel clear to transmit on?
@ -638,19 +635,33 @@ static void PIOS_RFM22B_Supervisor(uint32_t rfm22b_id)
return;
}
/* Not a problem if we're waiting for a packet. */
if(rf_mode == RX_WAIT_SYNC_MODE)
/* If we're waiting for a receive, we just need to make sure that there are no packets waiting to be transmitted. */
if(rf_mode == RX_WAIT_PREAMBLE_MODE)
{
/* Start a packet transfer if one is available. */
PIOS_RFM22B_TxStart(rfm22b_id, 0);
return;
}
/* The radio must be locked up if the timer reaches 0 */
if(--(rfm22b_dev->supv_timer) != 0)
return;
++(rfm22b_dev->resets);
TX_LED_OFF;
TX_LED_OFF;
/* Clear the TX buffer in case we locked up in a transmit */
tx_data_wr = 0;
rfm22_init_normal(rfm22b_dev->deviceID, rfm22b_dev->cfg.minFrequencyHz, rfm22b_dev->cfg.maxFrequencyHz, 50000);
/* Start a packet transfer if one is available. */
if(!rfm22_txStart())
rf_mode = RX_WAIT_PREAMBLE_MODE;
PIOS_RFM22B_TxStart(rfm22b_id, 0);
if(rf_mode == RX_WAIT_PREAMBLE_MODE)
{
/* Otherwise, switch to RX mode */
/* Switch to RX mode */
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
}
}
@ -816,9 +827,10 @@ void rfm22_setNominalCarrierFrequency(uint32_t frequency_hz)
// *******
if (frequency_hz < lower_carrier_frequency_limit_Hz) frequency_hz = lower_carrier_frequency_limit_Hz;
else
if (frequency_hz > upper_carrier_frequency_limit_Hz) frequency_hz = upper_carrier_frequency_limit_Hz;
if (frequency_hz < lower_carrier_frequency_limit_Hz)
frequency_hz = lower_carrier_frequency_limit_Hz;
else if (frequency_hz > upper_carrier_frequency_limit_Hz)
frequency_hz = upper_carrier_frequency_limit_Hz;
if (frequency_hz < 480000000)
hbsel = 1;
@ -1107,7 +1119,7 @@ void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode)
// FIFO mode, GFSK modulation
uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo |
RFM22_mmc2_modtyp_gfsk);
RFM22_mmc2_modtyp_gfsk);
}
// empty the rx buffer
@ -1132,12 +1144,11 @@ void rfm22_setRxMode(uint8_t mode, bool multi_packet_mode)
// enable RX interrupts
rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_encrcerror | RFM22_ie1_enpkvalid |
RFM22_ie1_enrxffafull | RFM22_ie1_enfferr);
RFM22_ie1_enrxffafull | RFM22_ie1_enfferr);
rfm22_write(RFM22_interrupt_enable2, RFM22_ie2_enpreainval | RFM22_ie2_enpreaval |
RFM22_ie2_enswdet);
RFM22_ie2_enswdet);
// enable the receiver
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_rxon);
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_rxon);
exec_using_spi = FALSE;
@ -1177,7 +1188,7 @@ uint8_t rfm22_txStart()
PIOS_IRQ_Disable();
// Initialize the supervisor timer.
rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT;
rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT;
// disable interrupts
rfm22_write(RFM22_interrupt_enable1, 0x00);
@ -1204,11 +1215,11 @@ uint8_t rfm22_txStart()
// FIFO mode, GFSK modulation
uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo |
RFM22_mmc2_modtyp_gfsk);
RFM22_mmc2_modtyp_gfsk);
// set the tx power
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 |
RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power);
RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power);
// clear FIFOs
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
@ -1234,15 +1245,9 @@ uint8_t rfm22_txStart()
rf_mode = TX_DATA_MODE;
// enable TX interrupts
// rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem | RFM22_ie1_enfferr);
rfm22_write(RFM22_interrupt_enable1, RFM22_ie1_enpksent | RFM22_ie1_entxffaem);
// read interrupt status - clear interrupts
//rfm22_read(RFM22_interrupt_status1);
//rfm22_read(RFM22_interrupt_status2);
// enable the transmitter
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton | RFM22_opfc1_txon);
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon | RFM22_opfc1_txon);
// Re-ensable interrrupts.
@ -1263,20 +1268,18 @@ static void rfm22_setTxMode(uint8_t mode)
exec_using_spi = TRUE;
// *******************
// disable interrupts
rfm22_write(RFM22_interrupt_enable1, 0x00);
rfm22_write(RFM22_interrupt_enable2, 0x00);
// rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_xton); // READY mode
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon); // TUNE mode
// TUNE mode
rfm22_write(RFM22_op_and_func_ctrl1, RFM22_opfc1_pllon);
RX_LED_OFF;
// set the tx power
rfm22_write(RFM22_tx_power, RFM22_tx_pwr_papeaken | RFM22_tx_pwr_papeaklvl_1 |
RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power);
RFM22_tx_pwr_papeaklvl_0 | RFM22_tx_pwr_lna_sw | tx_power);
uint8_t fd_bit = rfm22_read(RFM22_modulation_mode_control2) & RFM22_mmc2_fd;
if (mode == TX_CARRIER_MODE)
@ -1293,13 +1296,10 @@ static void rfm22_setTxMode(uint8_t mode)
rfm22_write(RFM22_modulation_mode_control2, fd_bit | RFM22_mmc2_dtmod_fifo |
RFM22_mmc2_modtyp_gfsk);
// rfm22_write(0x72, reg_72[lookup_index]); // rfm22_frequency_deviation
// clear FIFOs
rfm22_write(RFM22_op_and_func_ctrl2, RFM22_opfc2_ffclrrx | RFM22_opfc2_ffclrtx);
rfm22_write(RFM22_op_and_func_ctrl2, 0x00);
// *******************
// add some data to the chips TX FIFO before enabling the transmitter
{
uint16_t rd = 0;
@ -1335,8 +1335,6 @@ static void rfm22_setTxMode(uint8_t mode)
tx_data_rd = rd;
}
// *******************
// reset the timer
rfm22_int_timer = 0;
@ -1380,73 +1378,34 @@ void rfm22_processRxInt(void)
return;
}
// Sync timeout. Restart RX mode.
if (rf_mode == RX_WAIT_SYNC_MODE && rfm22_int_timer >= timeout_sync_ms)
{
rfm22_int_time_outs++;
rfm22_setError("R_SYNC_TIMEOUT");
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
return;
}
// RX timeout. Restart RX mode.
if (rf_mode == RX_DATA_MODE && rfm22_int_timer >= timeout_data_ms)
{
rfm22_setError("MISSING_INTERRUPTS");
rfm22_int_time_outs++;
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
return;
}
// The module is not in RX mode. Restart RX mode.
if ((device_status & RFM22_ds_cps_mask) != RFM22_ds_cps_rx)
{
// the rf module is not in rx mode
if (rfm22_int_timer >= 100)
{
rfm22_int_time_outs++;
// reset the receiver
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
return;
}
}
// Valid preamble detected
if (int_stat2 & RFM22_is2_ipreaval)
if (int_stat2 & RFM22_is2_ipreaval && (rf_mode == RX_WAIT_PREAMBLE_MODE))
{
if (rf_mode == RX_WAIT_PREAMBLE_MODE)
{
rfm22_int_timer = 0; // reset the timer
rf_mode = RX_WAIT_SYNC_MODE;
RX_LED_ON;
rfm22_setDebug("pream_det");
}
rf_mode = RX_WAIT_SYNC_MODE;
RX_LED_ON;
rfm22_setDebug("pream_det");
}
// Sync word detected
if (int_stat2 & RFM22_is2_iswdet)
if (int_stat2 & RFM22_is2_iswdet && ((rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE)))
{
if (rf_mode == RX_WAIT_PREAMBLE_MODE || rf_mode == RX_WAIT_SYNC_MODE)
{
rfm22_int_timer = 0; // reset the timer
rf_mode = RX_DATA_MODE;
RX_LED_ON;
rfm22_setDebug("sync_det");
rf_mode = RX_DATA_MODE;
RX_LED_ON;
rfm22_setDebug("sync_det");
// read the 10-bit signed afc correction value
// bits 9 to 2
afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8;
// bits 1 & 0
afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0;
afc_correction >>= 6;
// convert the afc value to Hz
afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f);
// read the 10-bit signed afc correction value
// bits 9 to 2
afc_correction = (uint16_t)rfm22_read(RFM22_afc_correction_read) << 8;
// bits 1 & 0
afc_correction |= (uint16_t)rfm22_read(RFM22_ook_counter_value1) & 0x00c0;
afc_correction >>= 6;
// convert the afc value to Hz
afc_correction_Hz = (int32_t)(frequency_step_size * afc_correction + 0.5f);
// remember the rssi for this packet
rx_packet_start_rssi_dBm = rssi_dBm;
// remember the afc value for this packet
rx_packet_start_afc_Hz = afc_correction_Hz;
}
// remember the rssi for this packet
rx_packet_start_rssi_dBm = rssi_dBm;
// remember the afc value for this packet
rx_packet_start_afc_Hz = afc_correction_Hz;
}
// RX FIFO almost full, it needs emptying
@ -1455,8 +1414,6 @@ void rfm22_processRxInt(void)
if (rf_mode == RX_DATA_MODE)
{
// read data from the rf chips FIFO buffer
rfm22_int_timer = 0; // reset the timer
// read the total length of the packet data
uint16_t len = rfm22_read(RFM22_received_packet_length);
@ -1500,23 +1457,9 @@ void rfm22_processRxInt(void)
return;
}
// if (int_stat2 & RFM22_is2_irssi)
// { // RSSI level is >= the set threshold
// }
// if (device_status & RFM22_ds_rxffem)
// { // RX FIFO empty
// }
// if (device_status & RFM22_ds_headerr)
// { // Header check error
// }
// Valid packet received
if (int_stat1 & RFM22_is1_ipkvalid)
{
// reset the timer
rfm22_int_timer = 0;
// read the total length of the packet data
register uint16_t len = rfm22_read(RFM22_received_packet_length);
@ -1536,6 +1479,7 @@ void rfm22_processRxInt(void)
// we have a packet length error .. discard the packet
rfm22_setError("r_pack_len_error");
debug_val = len;
rfm22_setRxMode(RX_WAIT_PREAMBLE_MODE, false);
return;
}
@ -1555,7 +1499,7 @@ void rfm22_processRxInt(void)
bool need_yield = false;
if (rfm22b_dev_g->rx_in_cb)
(rfm22b_dev_g->rx_in_cb)(rfm22b_dev_g->rx_in_context, (uint8_t*)rx_buffer,
rx_buffer_wr, NULL, &need_yield);
rx_buffer_wr, NULL, &need_yield);
rx_buffer_wr = 0;
}
@ -1647,10 +1591,7 @@ static void rfm22_processInt(void)
exec_using_spi = TRUE;
// Reset the supervisor timer.
rfm22b_dev->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT;
// ********************************
// read the RF modules current status registers
rfm22b_dev_g->supv_timer = PIOS_RFM22B_SUPERVISOR_TIMEOUT;
// read interrupt status registers - clears the interrupt line
int_status1 = rfm22_read(RFM22_interrupt_status1);
@ -1664,22 +1605,16 @@ static void rfm22_processInt(void)
// Read the RSSI if we're in RX mode
if (rf_mode != TX_DATA_MODE && rf_mode != TX_STREAM_MODE &&
rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE)
rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE)
{
// read rx signal strength .. 45 = -100dBm, 205 = -20dBm
rssi = rfm22_read(RFM22_rssi);
// convert to dBm
rssi_dBm = (int8_t)(rssi >> 1) - 122;
// calibrate the RSSI value (rf bandwidth appears to affect it)
// if (rf_bandwidth_used > 0)
// rssi_dBm -= 10000 / rf_bandwidth_used;
}
else
{
// read the tx power register
tx_pwr = rfm22_read(RFM22_tx_power);
}
// the RF module has gone and done a reset - we need to re-initialize the rf module
if (int_status2 & RFM22_is2_ipor)
@ -1850,8 +1785,8 @@ bool rfm22_txReady(void)
return FALSE;
return (tx_data_rd == 0 && tx_data_wr == 0 && rf_mode != TX_DATA_MODE &&
rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE &&
rf_mode != RX_SCAN_SPECTRUM);
rf_mode != TX_STREAM_MODE && rf_mode != TX_CARRIER_MODE && rf_mode != TX_PN_MODE &&
rf_mode != RX_SCAN_SPECTRUM);
}
// ************************************

View File

@ -73,6 +73,7 @@ uint16_t PIOS_WDG_Init()
// watchdog flags now stored in backup registers
PWR_BackupAccessCmd(ENABLE);
BKP_WriteBackupRegister(PIOS_WDG_REGISTER, 0x0);
wdg_configuration.bootup_flags = BKP_ReadBackupRegister(PIOS_WDG_REGISTER);
#endif
return delay;

View File

@ -37,6 +37,7 @@ struct flashfs_cfg {
uint32_t obj_table_start;
uint32_t obj_table_end;
uint32_t sector_size;
uint32_t chip_size;
};
int32_t PIOS_FLASHFS_Init(const struct flashfs_cfg * cfg);

View File

@ -300,6 +300,7 @@ void PIOS_Board_Init(void) {
}
}
#endif /* PIOS_INCLUDE_PPM */
break;
case PIPXSETTINGS_FLEXICONFIG_PPM_OUT:
case PIPXSETTINGS_FLEXICONFIG_RSSI:
case PIPXSETTINGS_FLEXICONFIG_DISABLED:

View File

@ -0,0 +1,12 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>RemoteSystemsTempFiles</name>
<comment></comment>
<projects>
</projects>
<buildSpec>
</buildSpec>
<natures>
<nature>org.eclipse.rse.ui.remoteSystemsTempNature</nature>
</natures>
</projectDescription>

View File

@ -277,6 +277,7 @@ static const struct flashfs_cfg flashfs_m25p_cfg = {
.obj_table_start = 0x00000010,
.obj_table_end = 0x00010000,
.sector_size = 0x00010000,
.chip_size = 0x00200000,
};
static const struct pios_flash_jedec_cfg flash_m25p_cfg = {

View File

@ -1,53 +1,53 @@
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file openpilot.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main OpenPilot header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef OPENPILOT_H
#define OPENPILOT_H
/* PIOS Includes */
#include <pios.h>
/* OpenPilot Libraries */
#include "op_config.h"
#include "utlist.h"
#include "uavobjectmanager.h"
#include "eventdispatcher.h"
#include "alarms.h"
#include "taskmonitor.h"
#include "uavtalk.h"
/* Global Functions */
void OpenPilotInit(void);
#endif /* OPENPILOT_H */
/**
* @}
* @}
*/
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file openpilot.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main OpenPilot header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef OPENPILOT_H
#define OPENPILOT_H
/* PIOS Includes */
#include <pios.h>
/* OpenPilot Libraries */
#include "op_config.h"
#include "utlist.h"
#include "uavobjectmanager.h"
#include "eventdispatcher.h"
#include "alarms.h"
#include "taskmonitor.h"
#include "uavtalk.h"
/* Global Functions */
void OpenPilotInit(void);
#endif /* OPENPILOT_H */
/**
* @}
* @}
*/

View File

@ -74,8 +74,8 @@ typedef enum {
*
* Bit(s) Name Meaning
* ------ ---- -------
* 0 access Defines the access level for the local transactions (readonly=0 and readwrite=1)
* 1 gcsAccess Defines the access level for the local GCS transactions (readonly=0 and readwrite=1), not used in the flight s/w
* 0 access Defines the access level for the local transactions (readonly=1 and readwrite=0)
* 1 gcsAccess Defines the access level for the local GCS transactions (readonly=1 and readwrite=0), not used in the flight s/w
* 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked)
* 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked)
* 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode)

View File

@ -721,10 +721,11 @@ int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId)
return -1;
// Fire event on success
if (PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0)
int32_t retval;
if ((retval = PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data)) == 0)
sendEvent(objEntry, instId, EV_UNPACKED);
else
return -1;
return retval;
#endif
#if defined(PIOS_INCLUDE_SDCARD)

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>796</width>
<height>605</height>
<width>730</width>
<height>602</height>
</rect>
</property>
<property name="windowTitle">
@ -1359,7 +1359,7 @@ margin:1px;</string>
<number>0</number>
</property>
<item>
<widget class="ConfigccpmWidget" name="widget_3" native="true"/>
<widget class="ConfigCcpmWidget" name="widget_3" native="true"/>
</item>
</layout>
</item>
@ -2893,7 +2893,7 @@ p, li { white-space: pre-wrap; }
<container>1</container>
</customwidget>
<customwidget>
<class>ConfigccpmWidget</class>
<class>ConfigCcpmWidget</class>
<extends>QWidget</extends>
<header>cfg_vehicletypes/configccpmwidget.h</header>
<container>1</container>
@ -2999,22 +2999,6 @@ p, li { white-space: pre-wrap; }
</hint>
</hints>
</connection>
<connection>
<sender>mrPitchMixLevel</sender>
<signal>valueChanged(int)</signal>
<receiver>mrPitchMixValue</receiver>
<slot>setNum(int)</slot>
<hints>
<hint type="sourcelabel">
<x>83</x>
<y>228</y>
</hint>
<hint type="destinationlabel">
<x>82</x>
<y>168</y>
</hint>
</hints>
</connection>
<connection>
<sender>mrRollMixLevel</sender>
<signal>valueChanged(int)</signal>
@ -3047,5 +3031,21 @@ p, li { white-space: pre-wrap; }
</hint>
</hints>
</connection>
<connection>
<sender>mrPitchMixLevel</sender>
<signal>valueChanged(int)</signal>
<receiver>mrPitchMixValue</receiver>
<slot>setNum(int)</slot>
<hints>
<hint type="sourcelabel">
<x>92</x>
<y>222</y>
</hint>
<hint type="destinationlabel">
<x>92</x>
<y>151</y>
</hint>
</hints>
</connection>
</connections>
</ui>

View File

@ -3959,7 +3959,7 @@ margin:1px;</string>
<connections>
<connection>
<sender>ccpmCollectiveSlider</sender>
<signal>sliderMoved(int)</signal>
<signal>valueChanged(int)</signal>
<receiver>ccpmCollectivespinBox</receiver>
<slot>setValue(int)</slot>
<hints>
@ -4007,7 +4007,7 @@ margin:1px;</string>
</connection>
<connection>
<sender>ccpmRevoSlider</sender>
<signal>sliderMoved(int)</signal>
<signal>valueChanged(int)</signal>
<receiver>ccpmREVOspinBox</receiver>
<slot>setValue(int)</slot>
<hints>
@ -4023,7 +4023,7 @@ margin:1px;</string>
</connection>
<connection>
<sender>SwashLvlPositionSlider</sender>
<signal>sliderMoved(int)</signal>
<signal>valueChanged(int)</signal>
<receiver>SwashLvlPositionSpinBox</receiver>
<slot>setValue(int)</slot>
<hints>
@ -4071,7 +4071,7 @@ margin:1px;</string>
</connection>
<connection>
<sender>ccpmCollectiveScale</sender>
<signal>sliderMoved(int)</signal>
<signal>valueChanged(int)</signal>
<receiver>ccpmCollectiveScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>
@ -4087,7 +4087,7 @@ margin:1px;</string>
</connection>
<connection>
<sender>ccpmCyclicScale</sender>
<signal>sliderMoved(int)</signal>
<signal>valueChanged(int)</signal>
<receiver>ccpmCyclicScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>
@ -4119,7 +4119,7 @@ margin:1px;</string>
</connection>
<connection>
<sender>ccpmPitchScale</sender>
<signal>sliderMoved(int)</signal>
<signal>valueChanged(int)</signal>
<receiver>ccpmPitchScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>
@ -4167,7 +4167,7 @@ margin:1px;</string>
</connection>
<connection>
<sender>ccpmRollScale</sender>
<signal>sliderMoved(int)</signal>
<signal>valueChanged(int)</signal>
<receiver>ccpmRollScaleBox</receiver>
<slot>setValue(int)</slot>
<hints>

View File

@ -25,7 +25,7 @@
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "configccpmwidget.h"
#include "mixersettings.h"
//#include "mixersettings.h"
#include <QDebug>
#include <QStringList>
@ -44,21 +44,17 @@
#define Pi 3.14159265358979323846
ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent)
{
int i;
m_ccpm = new Ui_ccpmWidget();
m_ccpm->setupUi(this);
SwashLvlConfigurationInProgress=0;
SwashLvlState=0;
SwashLvlServoInterlock=0;
updatingFromHardware=FALSE;
updatingToHardware=FALSE;
// Now connect the widget to the ManualControlCommand / Channel UAVObject
//ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
//UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
m_ccpm = new Ui_ccpmWidget();
m_ccpm->setupUi(this);
// Initialization of the swashplaye widget
m_ccpm->SwashplateImage->setScene(new QGraphicsScene(this));
@ -147,21 +143,18 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
UAVObjectField * curve2source = mixerSettings->getField("Curve2Source");
Q_ASSERT(curve2source);
QStringList channels;
channels << "Channel1" << "Channel2" << "Channel3" << "Channel4" <<
"Channel5" << "Channel6" << "Channel7" << "Channel8" << "None";
m_ccpm->ccpmEngineChannel->addItems(channels);
m_ccpm->ccpmEngineChannel->setCurrentIndex(8);
m_ccpm->ccpmTailChannel->addItems(channels);
m_ccpm->ccpmTailChannel->setCurrentIndex(8);
m_ccpm->ccpmServoWChannel->addItems(channels);
m_ccpm->ccpmServoWChannel->setCurrentIndex(8);
m_ccpm->ccpmServoXChannel->addItems(channels);
m_ccpm->ccpmServoXChannel->setCurrentIndex(8);
m_ccpm->ccpmServoYChannel->addItems(channels);
m_ccpm->ccpmServoYChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->addItems(channels);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmEngineChannel->addItems(channelNames);
m_ccpm->ccpmEngineChannel->setCurrentIndex(0);
m_ccpm->ccpmTailChannel->addItems(channelNames);
m_ccpm->ccpmTailChannel->setCurrentIndex(0);
m_ccpm->ccpmServoWChannel->addItems(channelNames);
m_ccpm->ccpmServoWChannel->setCurrentIndex(0);
m_ccpm->ccpmServoXChannel->addItems(channelNames);
m_ccpm->ccpmServoXChannel->setCurrentIndex(0);
m_ccpm->ccpmServoYChannel->addItems(channelNames);
m_ccpm->ccpmServoYChannel->setCurrentIndex(0);
m_ccpm->ccpmServoZChannel->addItems(channelNames);
m_ccpm->ccpmServoZChannel->setCurrentIndex(0);
QStringList Types;
Types << QString::fromUtf8("CCPM 2 Servo 90º") << QString::fromUtf8("CCPM 3 Servo 90º") <<
@ -170,12 +163,14 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
QString::fromUtf8("Custom - User Angles") << QString::fromUtf8("Custom - Advanced Settings");
m_ccpm->ccpmType->addItems(Types);
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - 1);
requestccpmUpdate();
UpdateCurveSettings();
//disable changing number of points in curves until UAVObjects have more than 5
m_ccpm->NumCurvePoints->setEnabled(0);
refreshWidgetsValues(QString("HeliCP"));
UpdateType();
//connect(m_ccpm->saveccpmToSD, SIGNAL(clicked()), this, SLOT(saveccpmUpdate()));
@ -205,9 +200,6 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
connect(m_ccpm->CurveSettings, SIGNAL(cellChanged (int, int)), this, SLOT(UpdateCurveWidgets()));
connect(m_ccpm->TabObject, SIGNAL(currentChanged ( QWidget * )), this, SLOT(UpdateType()));
// connect(m_ccpm->SwashLvlSwashplateImage, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateRedraw()));
connect(m_ccpm->PitchCurve, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updatePitchCurveValue(QList<double>,double)));
connect(m_ccpm->ThrottleCurve, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateThrottleCurveValue(QList<double>,double)));
@ -216,6 +208,7 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
connect(m_ccpm->SwashLvlCancelButton, SIGNAL(clicked()), this, SLOT(SwashLvlCancelButtonPressed()));
connect(m_ccpm->SwashLvlFinishButton, SIGNAL(clicked()), this, SLOT(SwashLvlFinishButtonPressed()));
connect(m_ccpm->ccpmCollectivePassthrough, SIGNAL(clicked()),this, SLOT(SetUIComponentVisibilities()));
connect(m_ccpm->ccpmLinkCyclic, SIGNAL(clicked()), this, SLOT(SetUIComponentVisibilities()));
connect(m_ccpm->ccpmLinkRoll, SIGNAL(clicked()), this, SLOT(SetUIComponentVisibilities()));
@ -224,18 +217,96 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent)
ccpmSwashplateRedraw();
}
ConfigccpmWidget::~ConfigccpmWidget()
ConfigCcpmWidget::~ConfigCcpmWidget()
{
// Do nothing
}
void ConfigccpmWidget::UpdateType()
void ConfigCcpmWidget::setupUI(QString frameType)
{
}
void ConfigCcpmWidget::ResetActuators(GUIConfigDataUnion* configData)
{
configData->heli.Throttle = 0;
configData->heli.Tail = 0;
configData->heli.ServoIndexW = 0;
configData->heli.ServoIndexX = 0;
configData->heli.ServoIndexY = 0;
configData->heli.ServoIndexZ = 0;
}
QStringList ConfigCcpmWidget::getChannelDescriptions()
{
int i;
QStringList channelDesc;
// init a channel_numelem list of channel desc defaults
for (i=0; i < (int)(ConfigCcpmWidget::CHANNEL_NUMELEM); i++)
{
channelDesc.append(QString("-"));
}
// get the gui config data
GUIConfigDataUnion configData = GetConfigData();
heliGUISettingsStruct heli = configData.heli;
if (heli.Throttle > 0)
channelDesc[heli.Throttle - 1] = QString("Throttle");
if (heli.Tail > 0)
channelDesc[heli.Tail - 1] = QString("Tail");
switch(heli.FirstServoIndex)
{
case 0: //front
if (heli.ServoIndexW > 0)
channelDesc[heli.ServoIndexW - 1] = QString("Elevator");
if (heli.ServoIndexX > 0)
channelDesc[heli.ServoIndexX - 1] = QString("Roll1");
if (heli.ServoIndexY > 0)
channelDesc[heli.ServoIndexY - 1] = QString("Roll2");
break;
case 1: //right
if (heli.ServoIndexW > 0)
channelDesc[heli.ServoIndexW - 1] = QString("ServoW");
if (heli.ServoIndexX > 0)
channelDesc[heli.ServoIndexX - 1] = QString("ServoX");
if (heli.ServoIndexY > 0)
channelDesc[heli.ServoIndexY - 1] = QString("ServoY");
break;
case 2: //rear
if (heli.ServoIndexW > 0)
channelDesc[heli.ServoIndexW - 1] = QString("Elevator");
if (heli.ServoIndexX > 0)
channelDesc[heli.ServoIndexX - 1] = QString("Roll1");
if (heli.ServoIndexY > 0)
channelDesc[heli.ServoIndexY - 1] = QString("Roll2");
break;
case 3: //left
if (heli.ServoIndexW > 0)
channelDesc[heli.ServoIndexW - 1] = QString("ServoW");
if (heli.ServoIndexX > 0)
channelDesc[heli.ServoIndexX - 1] = QString("ServoX");
if (heli.ServoIndexY > 0)
channelDesc[heli.ServoIndexY - 1] = QString("ServoY");
break;
}
if (heli.ServoIndexZ > 0)
channelDesc[heli.ServoIndexZ - 1] = QString("ServoZ");
return channelDesc;
}
void ConfigCcpmWidget::UpdateType()
{
int TypeInt,SingleServoIndex,NumServosDefined;
QString TypeText;
double AdjustmentAngle=0;
UpdateCCPMOptionsFromUI();
SetUIComponentVisibilities();
TypeInt = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1;
@ -283,8 +354,8 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleZ->setValue(0);
m_ccpm->ccpmAngleY->setEnabled(0);
m_ccpm->ccpmAngleZ->setEnabled(0);
m_ccpm->ccpmServoYChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoYChannel->setCurrentIndex(0);
m_ccpm->ccpmServoZChannel->setCurrentIndex(0);
m_ccpm->ccpmServoYChannel->setEnabled(0);
m_ccpm->ccpmServoZChannel->setEnabled(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
@ -298,7 +369,7 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 180,360));
m_ccpm->ccpmAngleZ->setValue(0);
m_ccpm->ccpmAngleZ->setEnabled(0);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->setCurrentIndex(0);
m_ccpm->ccpmServoZChannel->setEnabled(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
NumServosDefined=3;
@ -323,7 +394,7 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 240,360));
m_ccpm->ccpmAngleZ->setValue(0);
m_ccpm->ccpmAngleZ->setEnabled(0);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->setCurrentIndex(0);
m_ccpm->ccpmServoZChannel->setEnabled(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
NumServosDefined=3;
@ -336,7 +407,7 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 220,360));
m_ccpm->ccpmAngleZ->setValue(0);
m_ccpm->ccpmAngleZ->setEnabled(0);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->setCurrentIndex(0);
m_ccpm->ccpmServoZChannel->setEnabled(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
NumServosDefined=3;
@ -350,8 +421,8 @@ void ConfigccpmWidget::UpdateType()
m_ccpm->ccpmAngleZ->setValue(0);
m_ccpm->ccpmAngleY->setEnabled(0);
m_ccpm->ccpmAngleZ->setEnabled(0);
m_ccpm->ccpmServoYChannel->setCurrentIndex(8);
m_ccpm->ccpmServoZChannel->setCurrentIndex(8);
m_ccpm->ccpmServoYChannel->setCurrentIndex(0);
m_ccpm->ccpmServoZChannel->setCurrentIndex(0);
m_ccpm->ccpmServoYChannel->setEnabled(0);
m_ccpm->ccpmServoZChannel->setEnabled(0);
//m_ccpm->ccpmCorrectionAngle->setValue(0);
@ -407,12 +478,12 @@ void ConfigccpmWidget::UpdateType()
/**
Resets a mixer curve
*/
void ConfigccpmWidget::resetMixer(MixerCurveWidget *mixer, int numElements)
void ConfigCcpmWidget::resetMixer(MixerCurveWidget *mixer, int numElements)
{
mixer->initLinearCurve(numElements,(double)1);
}
void ConfigccpmWidget::UpdateCurveWidgets()
void ConfigCcpmWidget::UpdateCurveWidgets()
{
int NumCurvePoints,i,Changed;
QList<double> curveValues;
@ -446,7 +517,7 @@ void ConfigccpmWidget::UpdateCurveWidgets()
if (Changed==1)m_ccpm->PitchCurve->setCurve(curveValues);
}
void ConfigccpmWidget::updatePitchCurveValue(QList<double> curveValues0,double Value0)
void ConfigCcpmWidget::updatePitchCurveValue(QList<double> curveValues0,double Value0)
{
Q_UNUSED(curveValues0);
Q_UNUSED(Value0);
@ -470,7 +541,7 @@ void ConfigccpmWidget::updatePitchCurveValue(QList<double> curveValues0,double V
}
void ConfigccpmWidget::updateThrottleCurveValue(QList<double> curveValues0,double Value0)
void ConfigCcpmWidget::updateThrottleCurveValue(QList<double> curveValues0,double Value0)
{
Q_UNUSED(curveValues0);
Q_UNUSED(Value0);
@ -495,7 +566,7 @@ void ConfigccpmWidget::updateThrottleCurveValue(QList<double> curveValues0,doubl
}
void ConfigccpmWidget::UpdateCurveSettings()
void ConfigCcpmWidget::UpdateCurveSettings()
{
int NumCurvePoints,i;
double scale;
@ -625,7 +696,7 @@ void ConfigccpmWidget::UpdateCurveSettings()
UpdateCurveWidgets();
}
void ConfigccpmWidget::GenerateCurve()
void ConfigCcpmWidget::GenerateCurve()
{
int NumCurvePoints,CurveToGenerate,i;
double value1, value2, value3, scale;
@ -695,7 +766,7 @@ void ConfigccpmWidget::GenerateCurve()
}
void ConfigccpmWidget::ccpmSwashplateRedraw()
void ConfigCcpmWidget::ccpmSwashplateRedraw()
{
double angle[CCPM_MAX_SWASH_SERVOS],CorrectionAngle,x,y,w,h,radius,CenterX,CenterY;
int used[CCPM_MAX_SWASH_SERVOS],defined[CCPM_MAX_SWASH_SERVOS],i;
@ -735,10 +806,10 @@ void ConfigccpmWidget::ccpmSwashplateRedraw()
defined[1]=(m_ccpm->ccpmServoXChannel->isEnabled());
defined[2]=(m_ccpm->ccpmServoYChannel->isEnabled());
defined[3]=(m_ccpm->ccpmServoZChannel->isEnabled());
used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()<8)&&(m_ccpm->ccpmServoWChannel->isEnabled()));
used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()<8)&&(m_ccpm->ccpmServoXChannel->isEnabled()));
used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()<8)&&(m_ccpm->ccpmServoYChannel->isEnabled()));
used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()<8)&&(m_ccpm->ccpmServoZChannel->isEnabled()));
used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()>0)&&(m_ccpm->ccpmServoWChannel->isEnabled()));
used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()>0)&&(m_ccpm->ccpmServoXChannel->isEnabled()));
used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()>0)&&(m_ccpm->ccpmServoYChannel->isEnabled()));
used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()>0)&&(m_ccpm->ccpmServoZChannel->isEnabled()));
angle[0]=(CorrectionAngle+180+m_ccpm->ccpmAngleW->value())*Pi/180.00;
angle[1]=(CorrectionAngle+180+m_ccpm->ccpmAngleX->value())*Pi/180.00;
angle[2]=(CorrectionAngle+180+m_ccpm->ccpmAngleY->value())*Pi/180.00;
@ -796,69 +867,14 @@ void ConfigccpmWidget::ccpmSwashplateRedraw()
//m_ccpm->SwashplateImage->fitInView(SwashplateImg, Qt::KeepAspectRatio);
}
void ConfigccpmWidget::ccpmSwashplateUpdate()
void ConfigCcpmWidget::ccpmSwashplateUpdate()
{
ccpmSwashplateRedraw();
SetUIComponentVisibilities();
UpdateMixer();
}
void ConfigccpmWidget::ccpmChannelCheck()
{
if((m_ccpm->ccpmServoWChannel->currentIndex()==8)&&(m_ccpm->ccpmServoWChannel->isEnabled()))
{
m_ccpm->ccpmServoWLabel->setText("<font color=red>Servo W</font>");
}
else
{
m_ccpm->ccpmServoWLabel->setText("<font color=black>Servo W</font>");
}
if((m_ccpm->ccpmServoXChannel->currentIndex()==8)&&(m_ccpm->ccpmServoXChannel->isEnabled()))
{
m_ccpm->ccpmServoXLabel->setText("<font color=red>Servo X</font>");
}
else
{
m_ccpm->ccpmServoXLabel->setText("<font color=black>Servo X</font>");
}
if((m_ccpm->ccpmServoYChannel->currentIndex()==8)&&(m_ccpm->ccpmServoYChannel->isEnabled()))
{
m_ccpm->ccpmServoYLabel->setText("<font color=red>Servo Y</font>");
}
else
{
m_ccpm->ccpmServoYLabel->setText("<font color=black>Servo Y</font>");
}
if((m_ccpm->ccpmServoZChannel->currentIndex()==8)&&(m_ccpm->ccpmServoZChannel->isEnabled()))
{
m_ccpm->ccpmServoZLabel->setText("<font color=red>Servo Z</font>");
}
else
{
m_ccpm->ccpmServoZLabel->setText("<font color=black>Servo Z</font>");
}
if((m_ccpm->ccpmEngineChannel->currentIndex()==8)&&(m_ccpm->ccpmEngineChannel->isEnabled()))
{
m_ccpm->ccpmEngineLabel->setText("<font color=red>Engine</font>");
}
else
{
m_ccpm->ccpmEngineLabel->setText("<font color=black>Engine</font>");
}
if((m_ccpm->ccpmTailChannel->currentIndex()==8)&&(m_ccpm->ccpmTailChannel->isEnabled()))
{
m_ccpm->ccpmTailLabel->setText("<font color=red>Tail Rotor</font>");
}
else
{
m_ccpm->ccpmTailLabel->setText("<font color=black>Tail Rotor</font>");
}
}
void ConfigccpmWidget::UpdateMixer()
void ConfigCcpmWidget::UpdateMixer()
{
bool useCCPM;
bool useCyclic;
@ -866,13 +882,14 @@ void ConfigccpmWidget::UpdateMixer()
float CollectiveConstant,PitchConstant,RollConstant,ThisAngle[6];
QString Channel;
ccpmChannelCheck();
UpdateCCPMOptionsFromUI();
useCCPM = !(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState);
useCyclic = GUIConfigData.heli.ccpmLinkRollState;
throwConfigError(QString("HeliCP"));
CollectiveConstant = (float)GUIConfigData.heli.SliderValue0 / 100.00;
GUIConfigDataUnion config = GetConfigData();
useCCPM = !(config.heli.ccpmCollectivePassthroughState || !config.heli.ccpmLinkCyclicState);
useCyclic = config.heli.ccpmLinkRollState;
CollectiveConstant = (float)config.heli.SliderValue0 / 100.00;
if (useCCPM)
{//cyclic = 1 - collective
@ -881,18 +898,18 @@ void ConfigccpmWidget::UpdateMixer()
}
else
{
PitchConstant = (float)GUIConfigData.heli.SliderValue1 / 100.00;;
PitchConstant = (float)config.heli.SliderValue1 / 100.00;;
if (useCyclic)
{
RollConstant = PitchConstant;
}
else
{
RollConstant = (float)GUIConfigData.heli.SliderValue2 / 100.00;;
RollConstant = (float)config.heli.SliderValue2 / 100.00;;
}
}
if (GUIConfigData.heli.SwasplateType>0)
if (config.heli.SwashplateType>0)
{//not advanced settings
//get the channel data from the ui
MixerChannelData[0] = m_ccpm->ccpmEngineChannel->currentIndex();
@ -914,18 +931,18 @@ void ConfigccpmWidget::UpdateMixer()
ThisEnable[4] = m_ccpm->ccpmServoYChannel->isEnabled();
ThisEnable[5] = m_ccpm->ccpmServoZChannel->isEnabled();
ServosText[0]->setPlainText(QString("%1").arg( MixerChannelData[2]+1 ));
ServosText[1]->setPlainText(QString("%1").arg( MixerChannelData[3]+1 ));
ServosText[2]->setPlainText(QString("%1").arg( MixerChannelData[4]+1 ));
ServosText[3]->setPlainText(QString("%1").arg( MixerChannelData[5]+1 ));
ServosText[0]->setPlainText(QString("%1").arg( MixerChannelData[2] ));
ServosText[1]->setPlainText(QString("%1").arg( MixerChannelData[3] ));
ServosText[2]->setPlainText(QString("%1").arg( MixerChannelData[4] ));
ServosText[3]->setPlainText(QString("%1").arg( MixerChannelData[5] ));
//go through the user data and update the mixer matrix
for (i=0;i<6;i++)
{
if ((MixerChannelData[i]<8)&&((ThisEnable[i])||(i<2)))
if ((MixerChannelData[i]>0)&&((ThisEnable[i])||(i<2)))
{
m_ccpm->ccpmAdvancedSettingsTable->item(i,0)->setText(QString("%1").arg( MixerChannelData[i]+1 ));
m_ccpm->ccpmAdvancedSettingsTable->item(i,0)->setText(QString("%1").arg( MixerChannelData[i] ));
//config the vector
if (i==0)
{//motor-engine
@ -947,8 +964,8 @@ void ConfigccpmWidget::UpdateMixer()
{//Swashplate
m_ccpm->ccpmAdvancedSettingsTable->item(i,1)->setText(QString("%1").arg(0));//ThrottleCurve1
m_ccpm->ccpmAdvancedSettingsTable->item(i,2)->setText(QString("%1").arg((int)(127.0*CollectiveConstant)));//ThrottleCurve2
m_ccpm->ccpmAdvancedSettingsTable->item(i,3)->setText(QString("%1").arg((int)(127.0*(RollConstant)*sin((180+GUIConfigData.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Roll
m_ccpm->ccpmAdvancedSettingsTable->item(i,4)->setText(QString("%1").arg((int)(127.0*(PitchConstant)*cos((GUIConfigData.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Pitch
m_ccpm->ccpmAdvancedSettingsTable->item(i,3)->setText(QString("%1").arg((int)(127.0*(RollConstant)*sin((180+config.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Roll
m_ccpm->ccpmAdvancedSettingsTable->item(i,4)->setText(QString("%1").arg((int)(127.0*(PitchConstant)*cos((config.heli.CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Pitch
m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(0));//Yaw
}
@ -970,246 +987,167 @@ void ConfigccpmWidget::UpdateMixer()
}
}
}
/**************************
* ccpm settings
**************************/
/*
Get the state of the UI check boxes and change the visibility of sliders
typedef struct {
uint SwasplateType:3;
uint FirstServoIndex:2;
uint CorrectionAngle:9;
uint ccpmCollectivePassthroughState:1;
uint ccpmLinkCyclicState:1;
uint ccpmLinkRollState:1;
uint CollectiveChannel:3;
uint padding:12;
} __attribute__((packed)) heliGUISettingsStruct;
*/
void ConfigccpmWidget::UpdateCCPMOptionsFromUI()
QString ConfigCcpmWidget::updateConfigObjects()
{
QString airframeType = "HeliCP";
bool useCCPM;
bool useCyclic;
if (updatingFromHardware) return;
if (updatingFromHardware == TRUE) return airframeType;
updatingFromHardware = TRUE;
//get the user options
GUIConfigDataUnion config = GetConfigData();
//swashplate config
GUIConfigData.heli.SwasplateType = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1;
GUIConfigData.heli.FirstServoIndex = m_ccpm->ccpmSingleServo->currentIndex();
config.heli.SwashplateType = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1;
config.heli.FirstServoIndex = m_ccpm->ccpmSingleServo->currentIndex();
//ccpm mixing options
GUIConfigData.heli.ccpmCollectivePassthroughState = m_ccpm->ccpmCollectivePassthrough->isChecked();
GUIConfigData.heli.ccpmLinkCyclicState = m_ccpm->ccpmLinkCyclic->isChecked();
GUIConfigData.heli.ccpmLinkRollState = m_ccpm->ccpmLinkRoll->isChecked();
useCCPM = !(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState);
useCyclic = GUIConfigData.heli.ccpmLinkRollState;
config.heli.ccpmCollectivePassthroughState = m_ccpm->ccpmCollectivePassthrough->isChecked();
config.heli.ccpmLinkCyclicState = m_ccpm->ccpmLinkCyclic->isChecked();
config.heli.ccpmLinkRollState = m_ccpm->ccpmLinkRoll->isChecked();
useCCPM = !(config.heli.ccpmCollectivePassthroughState || !config.heli.ccpmLinkCyclicState);
useCyclic = config.heli.ccpmLinkRollState;
//correction angle
GUIConfigData.heli.CorrectionAngle = m_ccpm->ccpmCorrectionAngle->value();
config.heli.CorrectionAngle = m_ccpm->ccpmCorrectionAngle->value();
//update sliders
if (useCCPM)
if (useCCPM)
{
GUIConfigData.heli.SliderValue0 = m_ccpm->ccpmCollectiveSlider->value();
config.heli.SliderValue0 = m_ccpm->ccpmCollectiveSlider->value();
}
else
{
GUIConfigData.heli.SliderValue0 = m_ccpm->ccpmCollectiveScale->value();
config.heli.SliderValue0 = m_ccpm->ccpmCollectiveScale->value();
}
if (useCyclic)
if (useCyclic)
{
GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmCyclicScale->value();
config.heli.SliderValue1 = m_ccpm->ccpmCyclicScale->value();
}
else
{
GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmPitchScale->value();
}
GUIConfigData.heli.SliderValue2 = m_ccpm->ccpmRollScale->value();
config.heli.SliderValue1 = m_ccpm->ccpmPitchScale->value();
}
config.heli.SliderValue2 = m_ccpm->ccpmRollScale->value();
//servo assignments
GUIConfigData.heli.ServoIndexW = m_ccpm->ccpmServoWChannel->currentIndex();
GUIConfigData.heli.ServoIndexX = m_ccpm->ccpmServoXChannel->currentIndex();
GUIConfigData.heli.ServoIndexY = m_ccpm->ccpmServoYChannel->currentIndex();
GUIConfigData.heli.ServoIndexZ = m_ccpm->ccpmServoZChannel->currentIndex();
config.heli.ServoIndexW = m_ccpm->ccpmServoWChannel->currentIndex();
config.heli.ServoIndexX = m_ccpm->ccpmServoXChannel->currentIndex();
config.heli.ServoIndexY = m_ccpm->ccpmServoYChannel->currentIndex();
config.heli.ServoIndexZ = m_ccpm->ccpmServoZChannel->currentIndex();
//throttle
config.heli.Throttle = m_ccpm->ccpmEngineChannel->currentIndex();
//tail
config.heli.Tail = m_ccpm->ccpmTailChannel->currentIndex();
SetConfigData(config);
updatingFromHardware = FALSE;
return airframeType;
}
void ConfigccpmWidget::UpdateCCPMUIFromOptions()
QString ConfigCcpmWidget::updateConfigObjectsFromWidgets() //UpdateCCPMOptionsFromUI()
{
QString airframeType = updateConfigObjects();
setMixer();
return airframeType;
}
void ConfigCcpmWidget::refreshWidgetsValues(QString frameType) //UpdateCCPMUIFromOptions()
{
Q_UNUSED(frameType);
GUIConfigDataUnion config = GetConfigData();
//swashplate config
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - (GUIConfigData.heli.SwasplateType +1));
m_ccpm->ccpmSingleServo->setCurrentIndex(GUIConfigData.heli.FirstServoIndex);
setComboCurrentIndex( m_ccpm->ccpmType, m_ccpm->ccpmType->count() - (config.heli.SwashplateType +1));
setComboCurrentIndex(m_ccpm->ccpmSingleServo, config.heli.FirstServoIndex);
//ccpm mixing options
m_ccpm->ccpmCollectivePassthrough->setChecked(GUIConfigData.heli.ccpmCollectivePassthroughState);
m_ccpm->ccpmLinkCyclic->setChecked(GUIConfigData.heli.ccpmLinkCyclicState);
m_ccpm->ccpmLinkRoll->setChecked(GUIConfigData.heli.ccpmLinkRollState);
m_ccpm->ccpmCollectivePassthrough->setChecked(config.heli.ccpmCollectivePassthroughState);
m_ccpm->ccpmLinkCyclic->setChecked(config.heli.ccpmLinkCyclicState);
m_ccpm->ccpmLinkRoll->setChecked(config.heli.ccpmLinkRollState);
//correction angle
m_ccpm->ccpmCorrectionAngle->setValue(GUIConfigData.heli.CorrectionAngle);
m_ccpm->ccpmCorrectionAngle->setValue(config.heli.CorrectionAngle);
//update sliders
m_ccpm->ccpmCollectiveScale->setValue(GUIConfigData.heli.SliderValue0);
m_ccpm->ccpmCollectiveScaleBox->setValue(GUIConfigData.heli.SliderValue0);
m_ccpm->ccpmCyclicScale->setValue(GUIConfigData.heli.SliderValue1);
m_ccpm->ccpmCyclicScaleBox->setValue(GUIConfigData.heli.SliderValue1);
m_ccpm->ccpmPitchScale->setValue(GUIConfigData.heli.SliderValue1);
m_ccpm->ccpmPitchScaleBox->setValue(GUIConfigData.heli.SliderValue1);
m_ccpm->ccpmRollScale->setValue(GUIConfigData.heli.SliderValue2);
m_ccpm->ccpmRollScaleBox->setValue(GUIConfigData.heli.SliderValue2);
m_ccpm->ccpmCollectiveSlider->setValue(GUIConfigData.heli.SliderValue0);
m_ccpm->ccpmCollectivespinBox->setValue(GUIConfigData.heli.SliderValue0);
m_ccpm->ccpmCollectiveScale->setValue(config.heli.SliderValue0);
m_ccpm->ccpmCollectiveScaleBox->setValue(config.heli.SliderValue0);
m_ccpm->ccpmCyclicScale->setValue(config.heli.SliderValue1);
m_ccpm->ccpmCyclicScaleBox->setValue(config.heli.SliderValue1);
m_ccpm->ccpmPitchScale->setValue(config.heli.SliderValue1);
m_ccpm->ccpmPitchScaleBox->setValue(config.heli.SliderValue1);
m_ccpm->ccpmRollScale->setValue(config.heli.SliderValue2);
m_ccpm->ccpmRollScaleBox->setValue(config.heli.SliderValue2);
m_ccpm->ccpmCollectiveSlider->setValue(config.heli.SliderValue0);
m_ccpm->ccpmCollectivespinBox->setValue(config.heli.SliderValue0);
//servo assignments
m_ccpm->ccpmServoWChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexW);
m_ccpm->ccpmServoXChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexX);
m_ccpm->ccpmServoYChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexY);
m_ccpm->ccpmServoZChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexZ);
setComboCurrentIndex(m_ccpm->ccpmServoWChannel, config.heli.ServoIndexW);
setComboCurrentIndex( m_ccpm->ccpmServoXChannel,config.heli.ServoIndexX);
setComboCurrentIndex( m_ccpm->ccpmServoYChannel,config.heli.ServoIndexY);
setComboCurrentIndex( m_ccpm->ccpmServoZChannel,config.heli.ServoIndexZ);
//throttle
setComboCurrentIndex( m_ccpm->ccpmEngineChannel, config.heli.Throttle);
//tail
setComboCurrentIndex( m_ccpm->ccpmTailChannel, config.heli.Tail);
getMixer();
}
void ConfigccpmWidget::SetUIComponentVisibilities()
void ConfigCcpmWidget::SetUIComponentVisibilities()
{
UpdateCCPMOptionsFromUI();
//set which sliders are user...
m_ccpm->ccpmRevoMixingBox->setVisible(0);
m_ccpm->ccpmPitchMixingBox->setVisible(!GUIConfigData.heli.ccpmCollectivePassthroughState && GUIConfigData.heli.ccpmLinkCyclicState);
m_ccpm->ccpmCollectiveScalingBox->setVisible(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState);
m_ccpm->ccpmPitchMixingBox->setVisible(!m_ccpm->ccpmCollectivePassthrough->isChecked() &&
m_ccpm->ccpmLinkCyclic->isChecked());
m_ccpm->ccpmLinkCyclic->setVisible(!GUIConfigData.heli.ccpmCollectivePassthroughState);
m_ccpm->ccpmCyclicScalingBox->setVisible((GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState) && GUIConfigData.heli.ccpmLinkRollState);
if (!GUIConfigData.heli.ccpmCollectivePassthroughState && GUIConfigData.heli.ccpmLinkCyclicState)
m_ccpm->ccpmCollectiveScalingBox->setVisible(m_ccpm->ccpmCollectivePassthrough->isChecked() || !m_ccpm->ccpmLinkCyclic->isChecked());
m_ccpm->ccpmLinkCyclic->setVisible(!m_ccpm->ccpmCollectivePassthrough->isChecked());
m_ccpm->ccpmCyclicScalingBox->setVisible((m_ccpm->ccpmCollectivePassthrough->isChecked() || !m_ccpm->ccpmLinkCyclic->isChecked()) &&
m_ccpm->ccpmLinkRoll->isChecked());
if (!m_ccpm->ccpmCollectivePassthrough->checkState() && m_ccpm->ccpmLinkCyclic->isChecked())
{
m_ccpm->ccpmPitchScalingBox->setVisible(0);
m_ccpm->ccpmRollScalingBox->setVisible(0);
m_ccpm->ccpmLinkRoll->setVisible(0);
}
else
{
m_ccpm->ccpmPitchScalingBox->setVisible(!GUIConfigData.heli.ccpmLinkRollState);
m_ccpm->ccpmRollScalingBox->setVisible(!GUIConfigData.heli.ccpmLinkRollState);
m_ccpm->ccpmPitchScalingBox->setVisible(!m_ccpm->ccpmLinkRoll->isChecked());
m_ccpm->ccpmRollScalingBox->setVisible(!m_ccpm->ccpmLinkRoll->isChecked());
m_ccpm->ccpmLinkRoll->setVisible(1);
}
}
/**
Request the current value of the SystemSettings which holds the ccpm type
*/
void ConfigccpmWidget::requestccpmUpdate()
void ConfigCcpmWidget::getMixer()
{
#define MaxAngleError 2
int MixerDataFromHeli[8][5];
quint8 MixerOutputType[8];
int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],ServoCurve2[4];
int NumServos=0;
if (SwashLvlConfigurationInProgress)return;
if (updatingToHardware)return;
updatingFromHardware=TRUE;
unsigned int i,j;
SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager());
Q_ASSERT(systemSettings);
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM ==
(sizeof(GUIConfigData.UAVObject) / sizeof(GUIConfigData.UAVObject[0])));
for(i = 0; i < SystemSettings::GUICONFIGDATA_NUMELEM; i++)
GUIConfigData.UAVObject[i]=systemSettingsData.GUIConfigData[i];
UpdateCCPMUIFromOptions();
int i;
// Get existing mixer settings
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
//go through the user data and update the mixer matrix
for (j=0;j<5;j++)
{
MixerDataFromHeli[0][j] = mixerSettingsData.Mixer1Vector[j];
MixerDataFromHeli[1][j] = mixerSettingsData.Mixer2Vector[j];
MixerDataFromHeli[2][j] = mixerSettingsData.Mixer3Vector[j];
MixerDataFromHeli[3][j] = mixerSettingsData.Mixer4Vector[j];
MixerDataFromHeli[4][j] = mixerSettingsData.Mixer5Vector[j];
MixerDataFromHeli[5][j] = mixerSettingsData.Mixer6Vector[j];
MixerDataFromHeli[6][j] = mixerSettingsData.Mixer7Vector[j];
MixerDataFromHeli[7][j] = mixerSettingsData.Mixer8Vector[j];
}
MixerOutputType[0] = mixerSettingsData.Mixer1Type;
MixerOutputType[1] = mixerSettingsData.Mixer2Type;
MixerOutputType[2] = mixerSettingsData.Mixer3Type;
MixerOutputType[3] = mixerSettingsData.Mixer4Type;
MixerOutputType[4] = mixerSettingsData.Mixer5Type;
MixerOutputType[5] = mixerSettingsData.Mixer6Type;
MixerOutputType[6] = mixerSettingsData.Mixer7Type;
MixerOutputType[7] = mixerSettingsData.Mixer8Type;
EngineChannel =-1;
TailRotorChannel =-1;
for (j=0;j<5;j++)
{
ServoChannels[j]=8;
ServoCurve2[j]=0;
ServoAngles[j]=0;
SortAngles[j]=j;
}
NumServos=0;
//process the data from Heli and try to figure out the settings...
for (i=0;i<8;i++)
{
//check if this is the engine... Throttle only
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_MOTOR)&&
(MixerDataFromHeli[i][0]>0)&&//ThrottleCurve1
(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
(MixerDataFromHeli[i][2]==0)&&//Roll
(MixerDataFromHeli[i][3]==0)&&//Pitch
(MixerDataFromHeli[i][4]==0))//Yaw
{
EngineChannel = i;
m_ccpm->ccpmEngineChannel->setCurrentIndex(i);
}
//check if this is the tail rotor... REVO and YAW
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&&
//(MixerDataFromHeli[i][0]!=0)&&//ThrottleCurve1
(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
(MixerDataFromHeli[i][2]==0)&&//Roll
(MixerDataFromHeli[i][3]==0)&&//Pitch
(MixerDataFromHeli[i][4]!=0))//Yaw
{
TailRotorChannel = i;
m_ccpm->ccpmTailChannel->setCurrentIndex(i);
m_ccpm->ccpmRevoSlider->setValue((MixerDataFromHeli[i][0]*100)/127);
m_ccpm->ccpmREVOspinBox->setValue((MixerDataFromHeli[i][0]*100)/127);
}
//check if this is a swashplate servo... Throttle is zero
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&&
(MixerDataFromHeli[i][0]==0)&&//ThrottleCurve1
//(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
//(MixerDataFromHeli[i][2]==0)&&//Roll
//(MixerDataFromHeli[i][3]==0)&&//Pitch
(MixerDataFromHeli[i][4]==0))//Yaw
{
ServoChannels[NumServos] = i;//record the channel for this servo
ServoCurve2[NumServos]=MixerDataFromHeli[i][1];//record the ThrottleCurve2 contribution to this servo
ServoAngles[NumServos]=NumServos*45;//make this 0 for the final version
NumServos++;
}
}
//get the settings for the curve from the mixer settings
for (i=0;i<5;i++)
@ -1221,7 +1159,7 @@ void ConfigccpmWidget::requestccpmUpdate()
}
updatingFromHardware=FALSE;
UpdateCCPMUIFromOptions();
ccpmSwashplateUpdate();
}
@ -1229,25 +1167,15 @@ void ConfigccpmWidget::requestccpmUpdate()
/**
Sends the config to the board (ccpm type)
*/
void ConfigccpmWidget::sendccpmUpdate()
void ConfigCcpmWidget::setMixer()
{
int i,j;
if (SwashLvlConfigurationInProgress)return;
updatingToHardware=TRUE;
//ShowDisclaimer(1);
UpdateCCPMOptionsFromUI();
if (updatingToHardware == TRUE) return;
updatingToHardware=TRUE;
// Store the data required to reconstruct
SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager());
Q_ASSERT(systemSettings);
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
systemSettingsData.GUIConfigData[0] = GUIConfigData.UAVObject[0];
systemSettingsData.GUIConfigData[1] = GUIConfigData.UAVObject[1];
systemSettings->setData(systemSettingsData);
systemSettings->updated();
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
Q_ASSERT(mixerSettings);
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
@ -1276,19 +1204,23 @@ void ConfigccpmWidget::sendccpmUpdate()
&mixerSettingsData.Mixer8Type
};
//reset all to Disabled
for (i=0; i<8; i++)
*mixerTypes[i] = 0;
//go through the user data and update the mixer matrix
for (i=0;i<6;i++)
{
if (MixerChannelData[i]<8)
if (MixerChannelData[i]>0)
{
//set the mixer type
*(mixerTypes[MixerChannelData[i]]) = i==0 ?
*(mixerTypes[MixerChannelData[i] - 1]) = i==0 ?
MixerSettings::MIXER1TYPE_MOTOR :
MixerSettings::MIXER1TYPE_SERVO;
//config the vector
for (j=0;j<5;j++)
mixers[MixerChannelData[i]][j] = m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt();
mixers[MixerChannelData[i] - 1][j] = m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt();
}
}
@ -1302,7 +1234,7 @@ void ConfigccpmWidget::sendccpmUpdate()
//mapping of collective input to curve 2...
//MixerSettings.Curve2Source = Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5
//check if we are using throttle or directly from a channel...
if (GUIConfigData.heli.ccpmCollectivePassthroughState)
if (m_ccpm->ccpmCollectivePassthrough->isChecked())
mixerSettingsData.Curve2Source = MixerSettings::CURVE2SOURCE_COLLECTIVE;
else
mixerSettingsData.Curve2Source = MixerSettings::CURVE2SOURCE_THROTTLE;
@ -1316,18 +1248,19 @@ void ConfigccpmWidget::sendccpmUpdate()
/**
Send ccpm type to the board and request saving to SD card
*/
void ConfigccpmWidget::saveccpmUpdate()
void ConfigCcpmWidget::saveccpmUpdate()
{
if (SwashLvlConfigurationInProgress)return;
ShowDisclaimer(0);
// Send update so that the latest value is saved
sendccpmUpdate();
//sendccpmUpdate();
setMixer();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
saveObjectToSD(obj);
}
void ConfigccpmWidget::resizeEvent(QResizeEvent* event)
void ConfigCcpmWidget::resizeEvent(QResizeEvent* event)
{
Q_UNUSED(event);
// Make the custom table columns autostretch:
@ -1339,7 +1272,7 @@ void ConfigccpmWidget::resizeEvent(QResizeEvent* event)
ccpmSwashplateRedraw();
}
void ConfigccpmWidget::showEvent(QShowEvent *event)
void ConfigCcpmWidget::showEvent(QShowEvent *event)
{
Q_UNUSED(event)
m_ccpm->ccpmAdvancedSettingsTable->resizeColumnsToContents();
@ -1351,7 +1284,7 @@ void ConfigccpmWidget::showEvent(QShowEvent *event)
}
void ConfigccpmWidget::SwashLvlStartButtonPressed()
void ConfigCcpmWidget::SwashLvlStartButtonPressed()
{
QMessageBox msgBox;
int i;
@ -1388,7 +1321,8 @@ void ConfigccpmWidget::SwashLvlStartButtonPressed()
//download the current settings to the OP hw
sendccpmUpdate();
//sendccpmUpdate();
setMixer();
//change control mode to gcs control / disarmed
//set throttle to 0
@ -1413,10 +1347,10 @@ void ConfigccpmWidget::SwashLvlStartButtonPressed()
oldSwashLvlConfiguration.ServoChannels[2]=m_ccpm->ccpmServoYChannel->currentIndex();
oldSwashLvlConfiguration.ServoChannels[3]=m_ccpm->ccpmServoZChannel->currentIndex();
//if servos are used
oldSwashLvlConfiguration.Used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()<8)&&(m_ccpm->ccpmServoWChannel->isEnabled()));
oldSwashLvlConfiguration.Used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()<8)&&(m_ccpm->ccpmServoXChannel->isEnabled()));
oldSwashLvlConfiguration.Used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()<8)&&(m_ccpm->ccpmServoYChannel->isEnabled()));
oldSwashLvlConfiguration.Used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()<8)&&(m_ccpm->ccpmServoZChannel->isEnabled()));
oldSwashLvlConfiguration.Used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()>0)&&(m_ccpm->ccpmServoWChannel->isEnabled()));
oldSwashLvlConfiguration.Used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()>0)&&(m_ccpm->ccpmServoXChannel->isEnabled()));
oldSwashLvlConfiguration.Used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()>0)&&(m_ccpm->ccpmServoYChannel->isEnabled()));
oldSwashLvlConfiguration.Used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()>0)&&(m_ccpm->ccpmServoZChannel->isEnabled()));
//min,neutral,max values for the servos
for (i=0;i<CCPM_MAX_SWASH_SERVOS;i++)
{
@ -1449,7 +1383,7 @@ void ConfigccpmWidget::SwashLvlStartButtonPressed()
}
void ConfigccpmWidget::SwashLvlNextButtonPressed()
void ConfigCcpmWidget::SwashLvlNextButtonPressed()
{
//ShowDisclaimer(2);
SwashLvlState++;
@ -1552,7 +1486,7 @@ void ConfigccpmWidget::SwashLvlNextButtonPressed()
break;
}
}
void ConfigccpmWidget::SwashLvlCancelButtonPressed()
void ConfigCcpmWidget::SwashLvlCancelButtonPressed()
{
int i;
SwashLvlState=0;
@ -1600,7 +1534,7 @@ void ConfigccpmWidget::SwashLvlCancelButtonPressed()
}
void ConfigccpmWidget::SwashLvlFinishButtonPressed()
void ConfigCcpmWidget::SwashLvlFinishButtonPressed()
{
int i;
@ -1644,7 +1578,7 @@ void ConfigccpmWidget::SwashLvlFinishButtonPressed()
}
int ConfigccpmWidget::ShowDisclaimer(int messageID)
int ConfigCcpmWidget::ShowDisclaimer(int messageID)
{
QMessageBox msgBox;
msgBox.setText("<font color=red><h1>Warning!!!</h2></font>");
@ -1693,7 +1627,7 @@ int ConfigccpmWidget::ShowDisclaimer(int messageID)
Toggles the channel testing mode by making the GCS take over
the ActuatorCommand objects
*/
void ConfigccpmWidget::enableSwashplateLevellingControl(bool state)
void ConfigCcpmWidget::enableSwashplateLevellingControl(bool state)
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
@ -1733,7 +1667,7 @@ void ConfigccpmWidget::enableSwashplateLevellingControl(bool state)
Sets the swashplate level to a given value based on current settings for Max, Neutral and Min values.
level ranges -1 to +1
*/
void ConfigccpmWidget::setSwashplateLevel(int percent)
void ConfigCcpmWidget::setSwashplateLevel(int percent)
{
if (percent<0)return;// -1;
if (percent>100)return;// -1;
@ -1768,7 +1702,7 @@ return;
}
void ConfigccpmWidget::SwashLvlSpinBoxChanged(int value)
void ConfigCcpmWidget::SwashLvlSpinBoxChanged(int value)
{
Q_UNUSED(value);
int i;
@ -1808,3 +1742,63 @@ void ConfigccpmWidget::SwashLvlSpinBoxChanged(int value)
return;
}
/**
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
*/
void ConfigCcpmWidget::throwConfigError(QString airframeType)
{
Q_UNUSED(airframeType);
if((m_ccpm->ccpmServoWChannel->currentIndex()==0)&&(m_ccpm->ccpmServoWChannel->isEnabled()))
{
m_ccpm->ccpmServoWLabel->setText("<font color=red>Servo W</font>");
}
else
{
m_ccpm->ccpmServoWLabel->setText("<font color=black>Servo W</font>");
}
if((m_ccpm->ccpmServoXChannel->currentIndex()==0)&&(m_ccpm->ccpmServoXChannel->isEnabled()))
{
m_ccpm->ccpmServoXLabel->setText("<font color=red>Servo X</font>");
}
else
{
m_ccpm->ccpmServoXLabel->setText("<font color=black>Servo X</font>");
}
if((m_ccpm->ccpmServoYChannel->currentIndex()==0)&&(m_ccpm->ccpmServoYChannel->isEnabled()))
{
m_ccpm->ccpmServoYLabel->setText("<font color=red>Servo Y</font>");
}
else
{
m_ccpm->ccpmServoYLabel->setText("<font color=black>Servo Y</font>");
}
if((m_ccpm->ccpmServoZChannel->currentIndex()==0)&&(m_ccpm->ccpmServoZChannel->isEnabled()))
{
m_ccpm->ccpmServoZLabel->setText("<font color=red>Servo Z</font>");
}
else
{
m_ccpm->ccpmServoZLabel->setText("<font color=black>Servo Z</font>");
}
if((m_ccpm->ccpmEngineChannel->currentIndex()==0)&&(m_ccpm->ccpmEngineChannel->isEnabled()))
{
m_ccpm->ccpmEngineLabel->setText("<font color=red>Engine</font>");
}
else
{
m_ccpm->ccpmEngineLabel->setText("<font color=black>Engine</font>");
}
if((m_ccpm->ccpmTailChannel->currentIndex()==0)&&(m_ccpm->ccpmTailChannel->isEnabled()))
{
m_ccpm->ccpmTailLabel->setText("<font color=red>Tail Rotor</font>");
}
else
{
m_ccpm->ccpmTailLabel->setText("<font color=black>Tail Rotor</font>");
}
}

View File

@ -29,6 +29,7 @@
#include "ui_ccpm.h"
#include "../uavobjectwidgetutils/configtaskwidget.h"
#include "cfg_vehicletypes/vehicleconfig.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
@ -50,36 +51,14 @@ typedef struct {
int Min[CCPM_MAX_SWASH_SERVOS];
} SwashplateServoSettingsStruct;
typedef struct {
uint SwasplateType:3;
uint FirstServoIndex:2;
uint CorrectionAngle:9;
uint ccpmCollectivePassthroughState:1;
uint ccpmLinkCyclicState:1;
uint ccpmLinkRollState:1;
uint SliderValue0:7;
uint SliderValue1:7;
uint SliderValue2:7;//41bits
uint ServoIndexW:4;
uint ServoIndexX:4;
uint ServoIndexY:4;
uint ServoIndexZ:4;//57bits
uint padding:7;
} __attribute__((packed)) heliGUISettingsStruct;
typedef union
{
uint UAVObject[2];//32bits * 2
heliGUISettingsStruct heli;//64bits
} GUIConfigDataUnion;
class ConfigccpmWidget: public ConfigTaskWidget
class ConfigCcpmWidget: public VehicleConfig
{
Q_OBJECT
public:
ConfigccpmWidget(QWidget *parent = 0);
~ConfigccpmWidget();
ConfigCcpmWidget(QWidget *parent = 0);
~ConfigCcpmWidget();
friend class ConfigVehicleTypeWidget;
@ -87,14 +66,6 @@ private:
Ui_ccpmWidget *m_ccpm;
QGraphicsSvgItem *SwashplateImg;
QGraphicsSvgItem *CurveImg;
//QGraphicsSvgItem *ServoW;
//QGraphicsSvgItem *ServoX;
//QGraphicsSvgItem *ServoY;
//QGraphicsSvgItem *ServoZ;
//QGraphicsTextItem *ServoWText;
//QGraphicsTextItem *ServoXText;
//QGraphicsTextItem *ServoYText;
//QGraphicsTextItem *ServoZText;
QGraphicsSvgItem *Servos[CCPM_MAX_SWASH_SERVOS];
QGraphicsTextItem *ServosText[CCPM_MAX_SWASH_SERVOS];
QGraphicsLineItem *ServoLines[CCPM_MAX_SWASH_SERVOS];
@ -109,8 +80,6 @@ private:
SwashplateServoSettingsStruct oldSwashLvlConfiguration;
SwashplateServoSettingsStruct newSwashLvlConfiguration;
GUIConfigDataUnion GUIConfigData;
int MixerChannelData[6];
int ShowDisclaimer(int messageID);
virtual void enableControls(bool enable) { Q_UNUSED(enable)}; // Not used by this widget
@ -118,7 +87,16 @@ private:
bool updatingFromHardware;
bool updatingToHardware;
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
QString updateConfigObjects();
private slots:
virtual void setupUI(QString airframeType);
virtual void refreshWidgetsValues(QString frameType);
virtual QString updateConfigObjectsFromWidgets();
virtual void throwConfigError(QString airframeType);
void ccpmSwashplateUpdate();
void ccpmSwashplateRedraw();
void UpdateCurveSettings();
@ -135,11 +113,10 @@ private:
void SwashLvlCancelButtonPressed();
void SwashLvlFinishButtonPressed();
void UpdateCCPMOptionsFromUI();
void UpdateCCPMUIFromOptions();
//void UpdateCCPMOptionsFromUI();
//void UpdateCCPMUIFromOptions();
void SetUIComponentVisibilities();
void ccpmChannelCheck();
void enableSwashplateLevellingControl(bool state);
void setSwashplateLevel(int percent);
@ -147,8 +124,8 @@ private:
virtual void refreshValues() {}; // Not used
public slots:
void requestccpmUpdate();
void sendccpmUpdate();
void getMixer();
void setMixer();
void saveccpmUpdate();
protected:

View File

@ -24,7 +24,7 @@
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
//#include "configfixedwingwidget.h"
#include "configfixedwingwidget.h"
#include "configvehicletypewidget.h"
#include "mixersettings.h"
@ -40,18 +40,38 @@
#include "mixersettings.h"
#include "systemsettings.h"
#include "actuatorsettings.h"
#include "actuatorcommand.h"
/**
Helper function to setup the UI
Constructor
*/
void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType)
ConfigFixedWingWidget::ConfigFixedWingWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent)
{
m_aircraft = aircraft;
}
/**
Destructor
*/
ConfigFixedWingWidget::~ConfigFixedWingWidget()
{
// Do nothing
}
/**
Virtual function to setup the UI
*/
void ConfigFixedWingWidget::setupUI(QString frameType)
{
Q_ASSERT(m_aircraft);
if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") {
// Setup the UI
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing"));
m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Fixed Wing"));
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
m_aircraft->fwRudder1ChannelBox->setEnabled(true);
m_aircraft->fwRudder1Label->setEnabled(true);
m_aircraft->fwRudder2ChannelBox->setEnabled(true);
@ -72,8 +92,8 @@ void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType)
m_aircraft->elevonMixBox->setHidden(true);
} else if (frameType == "FixedWingElevon" || frameType == "Elevon") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing"));
m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevon"));
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Fixed Wing"));
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon"));
m_aircraft->fwAileron1Label->setText("Elevon 1");
m_aircraft->fwAileron2Label->setText("Elevon 2");
m_aircraft->fwElevator1ChannelBox->setEnabled(false);
@ -91,8 +111,8 @@ void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType)
m_aircraft->elevonLabel2->setText("Pitch");
} else if (frameType == "FixedWingVtail" || frameType == "Vtail") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing"));
m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Vtail"));
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Fixed Wing"));
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail"));
m_aircraft->fwRudder1ChannelBox->setEnabled(false);
m_aircraft->fwRudder1Label->setEnabled(false);
m_aircraft->fwRudder2ChannelBox->setEnabled(false);
@ -111,12 +131,53 @@ void ConfigVehicleTypeWidget::setupFixedWingUI(QString frameType)
}
}
void ConfigFixedWingWidget::ResetActuators(GUIConfigDataUnion* configData)
{
configData->fixedwing.FixedWingPitch1 = 0;
configData->fixedwing.FixedWingPitch2 = 0;
configData->fixedwing.FixedWingRoll1 = 0;
configData->fixedwing.FixedWingRoll2 = 0;
configData->fixedwing.FixedWingYaw1 = 0;
configData->fixedwing.FixedWingYaw2 = 0;
configData->fixedwing.FixedWingThrottle = 0;
}
QStringList ConfigFixedWingWidget::getChannelDescriptions()
{
int i;
QStringList channelDesc;
// init a channel_numelem list of channel desc defaults
for (i=0; i < (int)(ConfigFixedWingWidget::CHANNEL_NUMELEM); i++)
{
channelDesc.append(QString("-"));
}
// get the gui config data
GUIConfigDataUnion configData = GetConfigData();
if (configData.fixedwing.FixedWingPitch1 > 0)
channelDesc[configData.fixedwing.FixedWingPitch1-1] = QString("FixedWingPitch1");
if (configData.fixedwing.FixedWingPitch2 > 0)
channelDesc[configData.fixedwing.FixedWingPitch2-1] = QString("FixedWingPitch2");
if (configData.fixedwing.FixedWingRoll1 > 0)
channelDesc[configData.fixedwing.FixedWingRoll1-1] = QString("FixedWingRoll1");
if (configData.fixedwing.FixedWingRoll2 > 0)
channelDesc[configData.fixedwing.FixedWingRoll2-1] = QString("FixedWingRoll2");
if (configData.fixedwing.FixedWingYaw1 > 0)
channelDesc[configData.fixedwing.FixedWingYaw1-1] = QString("FixedWingYaw1");
if (configData.fixedwing.FixedWingYaw2 > 0)
channelDesc[configData.fixedwing.FixedWingYaw2-1] = QString("FixedWingYaw2");
if (configData.fixedwing.FixedWingThrottle > 0)
channelDesc[configData.fixedwing.FixedWingThrottle-1] = QString("FixedWingThrottle");
return channelDesc;
}
/**
Helper function to update the UI widget objects
Virtual function to update the UI widget objects
*/
QString ConfigVehicleTypeWidget::updateFixedWingObjectsFromWidgets()
QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets()
{
QString airframeType = "FixedWing";
@ -136,7 +197,7 @@ QString ConfigVehicleTypeWidget::updateFixedWingObjectsFromWidgets()
//All airframe types must start with "FixedWing"
if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder" ) {
airframeType = "FixedWing";
setupFrameFixedWing( airframeType );
setupFrameFixedWing( airframeType );
} else if (m_aircraft->fixedWingType->currentText() == "Elevon") {
airframeType = "FixedWingElevon";
setupFrameElevon( airframeType );
@ -144,54 +205,33 @@ QString ConfigVehicleTypeWidget::updateFixedWingObjectsFromWidgets()
airframeType = "FixedWingVtail";
setupFrameVtail( airframeType );
}
// Now reflect those settings in the "Custom" panel as well
updateCustomAirframeUI();
return airframeType;
}
/**
Helper function to refresh the UI widget values
Virtual function to refresh the UI widget values
*/
void ConfigVehicleTypeWidget::refreshFixedWingWidgetsValues(QString frameType)
void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType)
{
UAVDataObject* obj;
UAVObjectField *field;
// Then retrieve how channels are setup
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
field = obj->getField(QString("FixedWingThrottle"));
Q_ASSERT(field);
m_aircraft->fwEngineChannelBox->setCurrentIndex(m_aircraft->fwEngineChannelBox->findText(field->getValue().toString()));
Q_ASSERT(m_aircraft);
GUIConfigDataUnion config = GetConfigData();
fixedGUISettingsStruct fixed = config.fixedwing;
// Then retrieve how channels are setup
setComboCurrentIndex(m_aircraft->fwEngineChannelBox, fixed.FixedWingThrottle);
setComboCurrentIndex(m_aircraft->fwAileron1ChannelBox, fixed.FixedWingRoll1);
setComboCurrentIndex(m_aircraft->fwAileron2ChannelBox, fixed.FixedWingRoll2);
setComboCurrentIndex(m_aircraft->fwElevator1ChannelBox, fixed.FixedWingPitch1);
setComboCurrentIndex(m_aircraft->fwElevator2ChannelBox, fixed.FixedWingPitch2);
setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1);
setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2);
UAVDataObject* obj;
UAVObjectField *field;
field = obj->getField(QString("FixedWingRoll1"));
Q_ASSERT(field);
m_aircraft->fwAileron1ChannelBox->setCurrentIndex(m_aircraft->fwAileron1ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingRoll2"));
Q_ASSERT(field);
m_aircraft->fwAileron2ChannelBox->setCurrentIndex(m_aircraft->fwAileron2ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingPitch1"));
Q_ASSERT(field);
m_aircraft->fwElevator1ChannelBox->setCurrentIndex(m_aircraft->fwElevator1ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingPitch2"));
Q_ASSERT(field);
m_aircraft->fwElevator2ChannelBox->setCurrentIndex(m_aircraft->fwElevator2ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingYaw1"));
Q_ASSERT(field);
m_aircraft->fwRudder1ChannelBox->setCurrentIndex(m_aircraft->fwRudder1ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingYaw2"));
Q_ASSERT(field);
m_aircraft->fwRudder2ChannelBox->setCurrentIndex(m_aircraft->fwRudder2ChannelBox->findText(field->getValue().toString()));
if (frameType == "FixedWingElevon") {
// If the airframe is elevon, restore the slider setting
// Find the channel number for Elevon1 (FixedWingRoll1)
@ -230,11 +270,11 @@ void ConfigVehicleTypeWidget::refreshFixedWingWidgetsValues(QString frameType)
Returns False if impossible to create the mixer.
*/
bool ConfigVehicleTypeWidget::setupFrameFixedWing(QString airframeType)
bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType)
{
// Check coherence:
//Show any config errors in GUI
throwFixedWingChannelConfigError(airframeType);
throwConfigError(airframeType);
// - At least Pitch and either Roll or Yaw
if (m_aircraft->fwEngineChannelBox->currentText() == "None" ||
@ -245,118 +285,67 @@ bool ConfigVehicleTypeWidget::setupFrameFixedWing(QString airframeType)
// m_aircraft->fwStatusLabel->setText("ERROR: check channel assignment");
return false;
}
// Now setup the channels:
resetActuators();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
// Elevator
UAVObjectField *field = obj->getField("FixedWingPitch1");
Q_ASSERT(field);
field->setValue(m_aircraft->fwElevator1ChannelBox->currentText());
field = obj->getField("FixedWingPitch2");
Q_ASSERT(field);
field->setValue(m_aircraft->fwElevator2ChannelBox->currentText());
// Aileron
field = obj->getField("FixedWingRoll1");
Q_ASSERT(field);
field->setValue(m_aircraft->fwAileron1ChannelBox->currentText());
field = obj->getField("FixedWingRoll2");
Q_ASSERT(field);
field->setValue(m_aircraft->fwAileron2ChannelBox->currentText());
// Rudder
field = obj->getField("FixedWingYaw1");
Q_ASSERT(field);
field->setValue(m_aircraft->fwRudder1ChannelBox->currentText());
// Throttle
field = obj->getField("FixedWingThrottle");
Q_ASSERT(field);
field->setValue(m_aircraft->fwEngineChannelBox->currentText());
// Now setup the channels:
obj->updated();
GUIConfigDataUnion config = GetConfigData();
ResetActuators(&config);
config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex();
config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex();
config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex();
config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex();
config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex();
config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex();
SetConfigData(config);
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
// ... and compute the matrix:
// In order to make code a bit nicer, we assume:
// - Channel dropdowns start with 'None', then 0 to 7
// 1. Assign the servo/motor/none for each channel
// Disable all
foreach(QString mixer, mixerTypes) {
field = obj->getField(mixer);
Q_ASSERT(field);
field->setValue("Disabled");
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
//motor
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR);
setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
//rudder
channel = m_aircraft->fwRudder1ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
//ailerons
channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1;
if (channel > -1) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127);
channel = m_aircraft->fwAileron2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127);
}
// and set only the relevant channels:
// Engine
int tmpVal = m_aircraft->fwEngineChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Motor");
field = obj->getField(mixerVectors.at(tmpVal));
// First of all reset the vector
resetField(field);
int ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(127, ti);
// Rudder
tmpVal = m_aircraft->fwRudder1ChannelBox->currentIndex()-1;
// tmpVal will be -1 if rudder is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(127, ti);
} // Else: we have no rudder, only ailerons, we're fine with it.
// Ailerons
tmpVal = m_aircraft->fwAileron1ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Roll");
field->setValue(127, ti);
// Only set Aileron 2 if Aileron 1 is defined
tmpVal = m_aircraft->fwAileron2ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Roll");
field->setValue(127, ti);
}
} // Else we have no ailerons. Our consistency check guarantees we have
// rudder in this case, so we're fine with it too.
// Elevator
tmpVal = m_aircraft->fwElevator1ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Pitch");
field->setValue(127, ti);
// Only set Elevator 2 if it is defined
tmpVal = m_aircraft->fwElevator2ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Pitch");
field->setValue(127, ti);
//elevators
channel = m_aircraft->fwElevator1ChannelBox->currentIndex()-1;
if (channel > -1) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 127);
channel = m_aircraft->fwElevator2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 127);
}
obj->updated();
m_aircraft->fwStatusLabel->setText("Mixer generated");
return true;
@ -367,11 +356,11 @@ bool ConfigVehicleTypeWidget::setupFrameFixedWing(QString airframeType)
/**
Setup Elevon
*/
bool ConfigVehicleTypeWidget::setupFrameElevon(QString airframeType)
bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType)
{
// Check coherence:
//Show any config errors in GUI
throwFixedWingChannelConfigError(airframeType);
throwConfigError(airframeType);
// - At least Aileron1 and Aileron 2, and engine
if (m_aircraft->fwEngineChannelBox->currentText() == "None" ||
@ -382,106 +371,64 @@ bool ConfigVehicleTypeWidget::setupFrameElevon(QString airframeType)
return false;
}
resetActuators();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
// Elevons
UAVObjectField *field = obj->getField("FixedWingRoll1");
Q_ASSERT(field);
field->setValue(m_aircraft->fwAileron1ChannelBox->currentText());
field = obj->getField("FixedWingRoll2");
Q_ASSERT(field);
field->setValue(m_aircraft->fwAileron2ChannelBox->currentText());
// Rudder 1 (can be None)
field = obj->getField("FixedWingYaw1");
Q_ASSERT(field);
field->setValue(m_aircraft->fwRudder1ChannelBox->currentText());
// Rudder 2 (can be None)
field = obj->getField("FixedWingYaw2");
Q_ASSERT(field);
field->setValue(m_aircraft->fwRudder2ChannelBox->currentText());
// Throttle
field = obj->getField("FixedWingThrottle");
Q_ASSERT(field);
field->setValue(m_aircraft->fwEngineChannelBox->currentText());
obj->updated();
GUIConfigDataUnion config = GetConfigData();
ResetActuators(&config);
config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex();
config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex();
config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex();
config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex();
config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex();
SetConfigData(config);
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
// Save the curve:
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
// ... and compute the matrix:
// In order to make code a bit nicer, we assume:
// - Channel dropdowns start with 'None', then 0 to 7
// 1. Assign the servo/motor/none for each channel
// Disable all
foreach(QString mixer, mixerTypes) {
field = obj->getField(mixer);
Q_ASSERT(field);
field->setValue("Disabled");
int channel;
double value;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
//motor
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR);
setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
//rudders
channel = m_aircraft->fwRudder1ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
channel = m_aircraft->fwRudder2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127);
//ailerons
channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1;
if (channel > -1) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
value = (double)(m_aircraft->elevonSlider2->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value);
value = (double)(m_aircraft->elevonSlider1->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value);
channel = m_aircraft->fwAileron2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
value = (double)(m_aircraft->elevonSlider2->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value);
value = (double)(m_aircraft->elevonSlider1->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value);
}
// and set only the relevant channels:
// Engine
int tmpVal = m_aircraft->fwEngineChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Motor");
field = obj->getField(mixerVectors.at(tmpVal));
// First of all reset the vector
resetField(field);
int ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(127, ti);
// Rudder 1
tmpVal = m_aircraft->fwRudder1ChannelBox->currentIndex()-1;
// tmpVal will be -1 if rudder 1 is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(127, ti);
} // Else: we have no rudder, only elevons, we're fine with it.
// Rudder 2
tmpVal = m_aircraft->fwRudder2ChannelBox->currentIndex()-1;
// tmpVal will be -1 if rudder 2 is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(-127, ti);
} // Else: we have no rudder, only elevons, we're fine with it.
tmpVal = m_aircraft->fwAileron1ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Pitch");
field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti);
ti = field->getElementNames().indexOf("Roll");
field->setValue((double)m_aircraft->elevonSlider1->value()*1.27,ti);
}
tmpVal = m_aircraft->fwAileron2ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Pitch");
field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti);
ti = field->getElementNames().indexOf("Roll");
field->setValue(-(double)m_aircraft->elevonSlider1->value()*1.27,ti);
}
obj->updated();
m_aircraft->fwStatusLabel->setText("Mixer generated");
return true;
}
@ -491,11 +438,11 @@ bool ConfigVehicleTypeWidget::setupFrameElevon(QString airframeType)
/**
Setup VTail
*/
bool ConfigVehicleTypeWidget::setupFrameVtail(QString airframeType)
bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
{
// Check coherence:
//Show any config errors in GUI
throwFixedWingChannelConfigError(airframeType);
throwConfigError(airframeType);
// - At least Pitch1 and Pitch2, and engine
if (m_aircraft->fwEngineChannelBox->currentText() == "None" ||
@ -506,97 +453,75 @@ bool ConfigVehicleTypeWidget::setupFrameVtail(QString airframeType)
return false;
}
resetActuators();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
// Elevons
UAVObjectField *field = obj->getField("FixedWingPitch1");
Q_ASSERT(field);
field->setValue(m_aircraft->fwElevator1ChannelBox->currentText());
field = obj->getField("FixedWingPitch2");
Q_ASSERT(field);
field->setValue(m_aircraft->fwElevator2ChannelBox->currentText());
field = obj->getField("FixedWingRoll1");
Q_ASSERT(field);
field->setValue(m_aircraft->fwAileron1ChannelBox->currentText());
field = obj->getField("FixedWingRoll2");
Q_ASSERT(field);
field->setValue(m_aircraft->fwAileron2ChannelBox->currentText());
// Throttle
field = obj->getField("FixedWingThrottle");
Q_ASSERT(field);
field->setValue(m_aircraft->fwEngineChannelBox->currentText());
obj->updated();
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
GUIConfigDataUnion config = GetConfigData();
ResetActuators(&config);
config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex();
config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex();
config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex();
config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex();
config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex();
SetConfigData(config);
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
// Save the curve:
// ... and compute the matrix:
// In order to make code a bit nicer, we assume:
// - Channel dropdowns start with 'None', then 0 to 7
// 1. Assign the servo/motor/none for each channel
// Disable all
foreach(QString mixer, mixerTypes) {
field = obj->getField(mixer);
Q_ASSERT(field);
field->setValue("Disabled");
int channel;
double value;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
//motor
channel = m_aircraft->fwEngineChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR);
setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
//rudders
channel = m_aircraft->fwRudder1ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
channel = m_aircraft->fwRudder2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127);
//ailerons
channel = m_aircraft->fwAileron1ChannelBox->currentIndex()-1;
if (channel > -1) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127);
channel = m_aircraft->fwAileron2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127);
}
// and set only the relevant channels:
// Engine
int tmpVal = m_aircraft->fwEngineChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Motor");
field = obj->getField(mixerVectors.at(tmpVal));
// First of all reset the vector
resetField(field);
int ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(127, ti);
tmpVal = m_aircraft->fwAileron1ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Roll");
field->setValue(127,ti);
//vtail
channel = m_aircraft->fwElevator1ChannelBox->currentIndex()-1;
if (channel > -1) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
value = (double)(m_aircraft->elevonSlider2->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value);
value = (double)(m_aircraft->elevonSlider1->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, value);
channel = m_aircraft->fwElevator2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO);
value = (double)(m_aircraft->elevonSlider2->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value);
value = (double)(m_aircraft->elevonSlider1->value()*1.27);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -value);
}
tmpVal = m_aircraft->fwAileron2ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Roll");
field->setValue(-127,ti);
}
// Now compute the VTail
tmpVal = m_aircraft->fwElevator1ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Pitch");
field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti);
ti = field->getElementNames().indexOf("Yaw");
field->setValue((double)m_aircraft->elevonSlider1->value()*1.27,ti);
tmpVal = m_aircraft->fwElevator2ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Pitch");
field->setValue((double)m_aircraft->elevonSlider2->value()*1.27, ti);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(-(double)m_aircraft->elevonSlider1->value()*1.27,ti);
obj->updated();
m_aircraft->fwStatusLabel->setText("Mixer generated");
return true;
}
@ -604,7 +529,7 @@ bool ConfigVehicleTypeWidget::setupFrameVtail(QString airframeType)
/**
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
*/
void ConfigVehicleTypeWidget::throwFixedWingChannelConfigError(QString airframeType)
void ConfigFixedWingWidget::throwConfigError(QString airframeType)
{
//Initialize configuration error flag
bool error=false;

View File

@ -0,0 +1,74 @@
/**
******************************************************************************
*
* @file configairframetwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief Airframe configuration panel
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CONFIGFIXEDWINGWIDGET_H
#define CONFIGFIXEDWINGWIDGET_H
#include "ui_airframe.h"
#include "../uavobjectwidgetutils/configtaskwidget.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
#include "uavtalk/telemetrymanager.h"
#include <QtGui/QWidget>
#include <QList>
#include <QItemDelegate>
class Ui_Widget;
class ConfigFixedWingWidget: public VehicleConfig
{
Q_OBJECT
public:
ConfigFixedWingWidget(Ui_AircraftWidget *aircraft = 0, QWidget *parent = 0);
~ConfigFixedWingWidget();
friend class ConfigVehicleTypeWidget;
private:
Ui_AircraftWidget *m_aircraft;
bool setupFrameFixedWing(QString airframeType);
bool setupFrameElevon(QString airframeType);
bool setupFrameVtail(QString airframeType);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
private slots:
virtual void setupUI(QString airframeType);
virtual void refreshWidgetsValues(QString frameType);
virtual QString updateConfigObjectsFromWidgets();
virtual void throwConfigError(QString airframeType);
protected:
};
#endif // CONFIGFIXEDWINGWIDGET_H

View File

@ -24,7 +24,7 @@
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
//#include "configgroundvehiclewidget.h"
#include "configgroundvehiclewidget.h"
#include "configvehicletypewidget.h"
#include "mixersettings.h"
@ -40,18 +40,35 @@
#include "mixersettings.h"
#include "systemsettings.h"
#include "actuatorsettings.h"
#include "actuatorcommand.h"
/**
Helper function to setup the UI
Constructor
*/
void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType)
ConfigGroundVehicleWidget::ConfigGroundVehicleWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent)
{
m_aircraft = aircraft;
}
/**
Destructor
*/
ConfigGroundVehicleWidget::~ConfigGroundVehicleWidget()
{
// Do nothing
}
/**
Virtual function to setup the UI
*/
void ConfigGroundVehicleWidget::setupUI(QString frameType)
{
m_aircraft->differentialSteeringMixBox->setHidden(true);
//STILL NEEDS WORK
// Setup the UI
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Ground"));
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Ground"));
m_aircraft->gvEngineChannelBox->setEnabled(false);
m_aircraft->gvEngineLabel->setEnabled(false);
@ -64,7 +81,7 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType)
m_aircraft->gvAileron2Label->setEnabled(false);
if (frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)"){ //Tank
m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Differential (tank)"));
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Differential (tank)"));
m_aircraft->gvMotor1ChannelBox->setEnabled(true);
m_aircraft->gvMotor1Label->setEnabled(true);
@ -89,7 +106,7 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType)
}
else if (frameType == "GroundVehicleMotorcycle" || frameType == "Motorcycle"){ //Motorcycle
m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Motorcycle"));
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Motorcycle"));
m_aircraft->gvMotor1ChannelBox->setEnabled(false);
m_aircraft->gvMotor1Label->setEnabled(false);
@ -113,7 +130,7 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType)
m_aircraft->gvThrottleCurve2GroupBox->setTitle("Rear throttle curve");
}
else {//Car
m_aircraft->groundVehicleType->setCurrentIndex(m_aircraft->groundVehicleType->findText("Turnable (car)"));
setComboCurrentIndex(m_aircraft->groundVehicleType, m_aircraft->groundVehicleType->findText("Turnable (car)"));
m_aircraft->gvMotor1ChannelBox->setEnabled(true);
m_aircraft->gvMotor1Label->setEnabled(true);
@ -137,12 +154,46 @@ void ConfigVehicleTypeWidget::setupGroundVehicleUI(QString frameType)
}
}
void ConfigGroundVehicleWidget::ResetActuators(GUIConfigDataUnion* configData)
{
configData->ground.GroundVehicleSteering1 = 0;
configData->ground.GroundVehicleSteering2 = 0;
configData->ground.GroundVehicleThrottle1 = 0;
configData->ground.GroundVehicleThrottle2 = 0;
}
QStringList ConfigGroundVehicleWidget::getChannelDescriptions()
{
int i;
QStringList channelDesc;
// init a channel_numelem list of channel desc defaults
for (i=0; i < (int)(ConfigGroundVehicleWidget::CHANNEL_NUMELEM); i++)
{
channelDesc.append(QString("-"));
}
// get the gui config data
GUIConfigDataUnion configData = GetConfigData();
if (configData.ground.GroundVehicleSteering1 > 0)
channelDesc[configData.ground.GroundVehicleSteering1-1] = QString("GroundSteering1");
if (configData.ground.GroundVehicleSteering2 > 0)
channelDesc[configData.ground.GroundVehicleSteering2-1] = QString("GroundSteering2");
if (configData.ground.GroundVehicleThrottle1 > 0)
channelDesc[configData.ground.GroundVehicleThrottle1-1] = QString("GroundThrottle1");
if (configData.ground.GroundVehicleThrottle2 > 0)
channelDesc[configData.ground.GroundVehicleThrottle2-1] = QString("GroundThrottle2");
return channelDesc;
}
/**
Helper function to update the UI widget objects
Virtual function to update the UI widget objects
*/
QString ConfigVehicleTypeWidget::updateGroundVehicleObjectsFromWidgets()
QString ConfigGroundVehicleWidget::updateConfigObjectsFromWidgets()
{
QString airframeType = "GroundVehicleCar";
@ -176,56 +227,29 @@ QString ConfigVehicleTypeWidget::updateGroundVehicleObjectsFromWidgets()
airframeType = "GroundVehicleMotorcycle";
setupGroundVehicleMotorcycle(airframeType);
}
// Now reflect those settings in the "Custom" panel as well
updateCustomAirframeUI();
return airframeType;
}
/**
Helper function to refresh the UI widget values
Virtual function to refresh the UI widget values
*/
void ConfigVehicleTypeWidget::refreshGroundVehicleWidgetsValues(QString frameType)
void ConfigGroundVehicleWidget::refreshWidgetsValues(QString frameType)
{
UAVDataObject* obj;
UAVObjectField *field;
GUIConfigDataUnion config = GetConfigData();
//THIS SECTION STILL NEEDS WORK. FOR THE MOMENT, USE THE FIXED-WING ONBOARD SETTING IN ORDER TO MINIMIZE CHANCES OF BOLLOXING REAL CODE
// Retrieve channel setup values
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
field = obj->getField(QString("FixedWingThrottle"));
Q_ASSERT(field);
m_aircraft->gvEngineChannelBox->setCurrentIndex(m_aircraft->gvEngineChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingRoll1"));
Q_ASSERT(field);
m_aircraft->gvAileron1ChannelBox->setCurrentIndex(m_aircraft->gvAileron1ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingRoll2"));
Q_ASSERT(field);
m_aircraft->gvAileron2ChannelBox->setCurrentIndex(m_aircraft->gvAileron2ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("GroundVehicleThrottle1"));
Q_ASSERT(field);
m_aircraft->gvMotor1ChannelBox->setCurrentIndex(m_aircraft->gvMotor1ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("GroundVehicleThrottle2"));
Q_ASSERT(field);
m_aircraft->gvMotor2ChannelBox->setCurrentIndex(m_aircraft->gvMotor2ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("GroundVehicleSteering1"));
Q_ASSERT(field);
m_aircraft->gvSteering1ChannelBox->setCurrentIndex(m_aircraft->gvSteering1ChannelBox->findText(field->getValue().toString()));
field = obj->getField(QString("GroundVehicleSteering2"));
Q_ASSERT(field);
m_aircraft->gvSteering2ChannelBox->setCurrentIndex(m_aircraft->gvSteering2ChannelBox->findText(field->getValue().toString()));
setComboCurrentIndex(m_aircraft->gvMotor1ChannelBox, config.ground.GroundVehicleThrottle1);
setComboCurrentIndex(m_aircraft->gvMotor2ChannelBox, config.ground.GroundVehicleThrottle2);
setComboCurrentIndex(m_aircraft->gvSteering1ChannelBox, config.ground.GroundVehicleSteering1);
setComboCurrentIndex(m_aircraft->gvSteering2ChannelBox, config.ground.GroundVehicleSteering2);
if (frameType == "GroundVehicleDifferential") {
//CURRENTLY BROKEN UNTIL WE DECIDE HOW DIFFERENTIAL SHOULD BEHAVE
// If the vehicle type is "differential", restore the slider setting
@ -233,14 +257,11 @@ void ConfigVehicleTypeWidget::refreshGroundVehicleWidgetsValues(QString frameTyp
// Find the channel number for Motor1
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
int chMixerNumber = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
if (chMixerNumber >= 0) { // If for some reason the actuators were incoherent, we might fail here, hence the check.
field = obj->getField(mixerVectors.at(chMixerNumber));
int ti = field->getElementNames().indexOf("Roll");
m_aircraft->differentialSteeringSlider1->setValue(field->getDouble(ti)*100);
ti = field->getElementNames().indexOf("Pitch");
m_aircraft->differentialSteeringSlider2->setValue(field->getDouble(ti)*100);
int channel = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check.
m_aircraft->differentialSteeringSlider1->setValue(getMixerVectorValue(obj,channel,VehicleConfig::MIXERVECTOR_ROLL)*100);
m_aircraft->differentialSteeringSlider2->setValue(getMixerVectorValue(obj,channel,VehicleConfig::MIXERVECTOR_PITCH)*100);
}
}
if (frameType == "GroundVehicleMotorcycle") {
@ -260,119 +281,62 @@ void ConfigVehicleTypeWidget::refreshGroundVehicleWidgetsValues(QString frameTyp
}
/**
Setup balancing ground vehicle.
Returns False if impossible to create the mixer.
*/
bool ConfigVehicleTypeWidget::setupGroundVehicleMotorcycle(QString airframeType){
bool ConfigGroundVehicleWidget::setupGroundVehicleMotorcycle(QString airframeType){
// Check coherence:
//Show any config errors in GUI
throwGroundVehicleChannelConfigError(airframeType);
throwConfigError(airframeType);
// - Motor, steering, and balance
if (m_aircraft->gvMotor1ChannelBox->currentText() == "None" ||
if (m_aircraft->gvMotor2ChannelBox->currentText() == "None" ||
(m_aircraft->gvSteering1ChannelBox->currentText() == "None" ||
m_aircraft->gvSteering2ChannelBox->currentText() == "None") )
{
return false;
}
// Now setup the channels:
resetActuators();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
// Left motor
UAVObjectField *field = obj->getField("GroundVehicleThrottle1");
Q_ASSERT(field);
field->setValue(m_aircraft->gvMotor1ChannelBox->currentText());
// Right motor
field = obj->getField("GroundVehicleThrottle2");
Q_ASSERT(field);
field->setValue(m_aircraft->gvMotor2ChannelBox->currentText());
obj->updated();
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
// ... and compute the matrix:
// In order to make code a bit nicer, we assume:
// - Channel dropdowns start with 'None', then 0 to 7
// 1. Assign the servo/motor/none for each channel
int tmpVal, ti;
// Disable all output channels
foreach(QString mixer, mixerTypes) {
field = obj->getField(mixer);
Q_ASSERT(field);
//Disable output channel
field->setValue("Disabled");
}
// Set all mixer values to zero
foreach(QString mixer, mixerVectors) {
field = obj->getField(mixer);
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("ThrottleCurve2");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Pitch");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Roll");
field->setValue(0, ti);
}
// Motor
// Setup motor
tmpVal = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo"); //Set motor mixer type to Servo
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve1"); //Set motor to full forward
field->setValue(127, ti);
//Steering
// Setup steering
tmpVal = m_aircraft->gvSteering1ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo"); //Set motor mixer type to Servo
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Yaw"); //Set steering response to roll
field->setValue(-127, ti);
ti = field->getElementNames().indexOf("Roll"); //Set steering response to roll
field->setValue(-127, ti);
//Balancing
// Setup balancing servo
tmpVal = m_aircraft->gvSteering2ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo"); //Set motor mixer type to Servo
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Yaw"); //Set balance response to yaw
field->setValue(127, ti);
ti = field->getElementNames().indexOf("Roll"); //Set balance response to roll
field->setValue(127, ti);
// Now setup the channels:
GUIConfigDataUnion config = GetConfigData();
ResetActuators(&config);
config.ground.GroundVehicleThrottle1 = m_aircraft->gvMotor1ChannelBox->currentIndex();
config.ground.GroundVehicleThrottle2 = m_aircraft->gvMotor2ChannelBox->currentIndex();
SetConfigData(config);
obj->updated();
//Output success message
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
//motor
channel = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
//steering
channel = m_aircraft->gvSteering1ChannelBox->currentIndex()-1;
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127);
//balance
channel = m_aircraft->gvSteering2ChannelBox->currentIndex()-1;
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127);
m_aircraft->gvStatusLabel->setText("Mixer generated");
return true;
@ -385,10 +349,10 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleMotorcycle(QString airframeType)
Returns False if impossible to create the mixer.
*/
bool ConfigVehicleTypeWidget::setupGroundVehicleDifferential(QString airframeType){
bool ConfigGroundVehicleWidget::setupGroundVehicleDifferential(QString airframeType){
// Check coherence:
//Show any config errors in GUI
throwGroundVehicleChannelConfigError(airframeType);
throwConfigError(airframeType);
// - Left and right steering
if ( m_aircraft->gvMotor2ChannelBox->currentText() == "None" ||
@ -397,86 +361,37 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleDifferential(QString airframeTyp
return false;
}
// Now setup the channels:
GUIConfigDataUnion config = GetConfigData();
ResetActuators(&config);
// Now setup the channels:
resetActuators();
config.ground.GroundVehicleThrottle1 = m_aircraft->gvMotor1ChannelBox->currentIndex();
config.ground.GroundVehicleThrottle2 = m_aircraft->gvMotor2ChannelBox->currentIndex();
SetConfigData((config));
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
// Left motor
UAVObjectField *field = obj->getField("GroundVehicleThrottle1");
Q_ASSERT(field);
field->setValue(m_aircraft->gvMotor1ChannelBox->currentText());
// Right motor
field = obj->getField("GroundVehicleThrottle2");
Q_ASSERT(field);
field->setValue(m_aircraft->gvMotor2ChannelBox->currentText());
obj->updated();
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
// ... and compute the matrix:
// In order to make code a bit nicer, we assume:
// - Channel dropdowns start with 'None', then 0 to 7
// 1. Assign the servo/motor/none for each channel
int tmpVal, ti;
// Disable all output channels
foreach(QString mixer, mixerTypes) {
field = obj->getField(mixer);
Q_ASSERT(field);
//Disable output channel
field->setValue("Disabled");
}
// Set all mixer values to zero
foreach(QString mixer, mixerVectors) {
field = obj->getField(mixer);
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("ThrottleCurve2");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Pitch");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Roll");
field->setValue(0, ti);
}
// Motor
// Setup left motor
tmpVal = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo"); //Set motor mixer type to Servo
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve1"); //Set motor to full forward
field->setValue(127, ti);
ti = field->getElementNames().indexOf("Yaw"); //Set motor to turn right with increasing throttle
field->setValue(127, ti);
// Setup right motor
tmpVal = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo"); //Set motor mixer type to Servo
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve2"); //Set motor to full forward
field->setValue(127, ti);
ti = field->getElementNames().indexOf("Yaw"); //Set motor to turn left with increasing throttle
field->setValue(-127, ti);
obj->updated();
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
//left motor
channel = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
//right motor
channel = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127);
//Output success message
m_aircraft->gvStatusLabel->setText("Mixer generated");
@ -492,11 +407,11 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleDifferential(QString airframeTyp
Returns False if impossible to create the mixer.
*/
bool ConfigVehicleTypeWidget::setupGroundVehicleCar(QString airframeType)
bool ConfigGroundVehicleWidget::setupGroundVehicleCar(QString airframeType)
{
// Check coherence:
//Show any config errors in GUI
throwGroundVehicleChannelConfigError(airframeType);
throwConfigError(airframeType);
// - At least one motor and one steering servo
if ((m_aircraft->gvMotor1ChannelBox->currentText() == "None" &&
@ -506,147 +421,43 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleCar(QString airframeType)
{
return false;
}
// else{
// // m_aircraft->gvStatusLabel->setText("Mixer generated");
// QTextEdit* htmlText=new QTextEdit(m_aircraft->gvSteering1Label->text()); // HtmlText is any QString with html tags.
// m_aircraft->gvSteering1Label->setText(htmlText->toPlainText());
// delete htmlText;
//
// htmlText=new QTextEdit(m_aircraft->gvSteering2Label->text()); // HtmlText is any QString with html tags.
// m_aircraft->gvSteering2Label->setText(htmlText->toPlainText());
// delete htmlText;
//
// htmlText=new QTextEdit(m_aircraft->gvMotor1Label->text()); // HtmlText is any QString with html tags.
// m_aircraft->gvMotor1Label->setText(htmlText->toPlainText());
// delete htmlText;
//
// htmlText=new QTextEdit(m_aircraft->gvMotor2Label->text()); // HtmlText is any QString with html tags.
// m_aircraft->gvMotor2Label->setText(htmlText->toPlainText());
// }
// Now setup the channels:
GUIConfigDataUnion config = GetConfigData();
ResetActuators(&config);
// Now setup the channels:
resetActuators();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
// Front motor
UAVObjectField *field = obj->getField("GroundVehicleThrottle1");
Q_ASSERT(field);
field->setValue(m_aircraft->gvMotor1ChannelBox->currentText());
// Rear motor
field = obj->getField("GroundVehicleThrottle2");
Q_ASSERT(field);
field->setValue(m_aircraft->gvMotor2ChannelBox->currentText());
config.ground.GroundVehicleThrottle1 = m_aircraft->gvMotor1ChannelBox->currentIndex();
config.ground.GroundVehicleThrottle2 = m_aircraft->gvMotor2ChannelBox->currentIndex();
config.ground.GroundVehicleSteering1 = m_aircraft->gvSteering1ChannelBox->currentIndex();
config.ground.GroundVehicleSteering2 = m_aircraft->gvSteering2ChannelBox->currentIndex();
// // Aileron
// field = obj->getField("FixedWingRoll1");
// Q_ASSERT(field);
// field->setValue(m_aircraft->fwAileron1ChannelBox->currentText());
//
// field = obj->getField("FixedWingRoll2");
// Q_ASSERT(field);
// field->setValue(m_aircraft->fwAileron2ChannelBox->currentText());
SetConfigData(config);
// Front steering
field = obj->getField("GroundVehicleSteering1");
Q_ASSERT(field);
field->setValue(m_aircraft->gvSteering1ChannelBox->currentText());
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
// Rear steering
field = obj->getField("GroundVehicleSteering2");
Q_ASSERT(field);
field->setValue(m_aircraft->gvSteering2ChannelBox->currentText());
obj->updated();
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
// ... and compute the matrix:
// In order to make code a bit nicer, we assume:
// - Channel dropdowns start with 'None', then 0 to 7
// 1. Assign the servo/motor/none for each channel
int tmpVal, ti;
// Disable all output channels
foreach(QString mixer, mixerTypes) {
field = obj->getField(mixer);
Q_ASSERT(field);
//Disable output channel
field->setValue("Disabled");
}
// Set all mixer values to zero
foreach(QString mixer, mixerVectors) {
field = obj->getField(mixer);
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("ThrottleCurve2");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Pitch");
field->setValue(0, ti);
ti = field->getElementNames().indexOf("Roll");
field->setValue(0, ti);
}
// Steering
// Only set front steering if it is defined
tmpVal = m_aircraft->gvSteering1ChannelBox->currentIndex()-1;
// tmpVal will be -1 if steering is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(127, ti);
} // Else: we have no front steering. We're fine with it as long as we have rear steering
// Only set rear steering if it is defined
tmpVal = m_aircraft->gvSteering2ChannelBox->currentIndex()-1;
// tmpVal will be -1 if steering is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("Yaw");
field->setValue(-127, ti);
} // Else: we have no rear steering. We're fine with it as long as we have front steering
// Motor
// Only set front motor if it is defined
tmpVal = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(127, ti);
}
// Only set rear motor if it is defined
tmpVal = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
if (tmpVal > -1) {
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
ti = field->getElementNames().indexOf("ThrottleCurve2");
field->setValue(127, ti);
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
obj->updated();
channel = m_aircraft->gvSteering1ChannelBox->currentIndex()-1;
setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
channel = m_aircraft->gvSteering2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127);
channel = m_aircraft->gvMotor1ChannelBox->currentIndex()-1;
setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
channel = m_aircraft->gvMotor2ChannelBox->currentIndex()-1;
setMixerType(mixer,channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 127);
//Output success message
m_aircraft->gvStatusLabel->setText("Mixer generated");
@ -657,7 +468,7 @@ bool ConfigVehicleTypeWidget::setupGroundVehicleCar(QString airframeType)
/**
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
*/
void ConfigVehicleTypeWidget::throwGroundVehicleChannelConfigError(QString airframeType)
void ConfigGroundVehicleWidget::throwConfigError(QString airframeType)
{
//Initialize configuration error flag
bool error=false;

View File

@ -0,0 +1,74 @@
/**
******************************************************************************
*
* @file configairframetwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief Airframe configuration panel
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CONFIGGROUNDVEHICLEWIDGET_H
#define CONFIGGROUNDVEHICLEWIDGET_H
#include "ui_airframe.h"
#include "../uavobjectwidgetutils/configtaskwidget.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
#include "uavtalk/telemetrymanager.h"
#include <QtGui/QWidget>
#include <QList>
#include <QItemDelegate>
class Ui_Widget;
class ConfigGroundVehicleWidget: public VehicleConfig
{
Q_OBJECT
public:
ConfigGroundVehicleWidget(Ui_AircraftWidget *aircraft = 0, QWidget *parent = 0);
~ConfigGroundVehicleWidget();
friend class ConfigVehicleTypeWidget;
private:
Ui_AircraftWidget *m_aircraft;
bool setupGroundVehicleCar(QString airframeType);
bool setupGroundVehicleDifferential(QString airframeType);
bool setupGroundVehicleMotorcycle(QString airframeType);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
private slots:
virtual void setupUI(QString airframeType);
virtual void refreshWidgetsValues(QString frameType);
virtual QString updateConfigObjectsFromWidgets();
virtual void throwConfigError(QString airframeType);
protected:
};
#endif // CONFIGGROUNDVEHICLEWIDGET_H

View File

@ -24,8 +24,7 @@
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
//#include "configmultirotorwidget.h"
#include "configvehicletypewidget.h"
#include "configmultirotorwidget.h"
#include "mixersettings.h"
#include <QDebug>
@ -34,200 +33,192 @@
#include <QtGui/QTextEdit>
#include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton>
#include <QtGui/QComboBox>
#include <QBrush>
#include <math.h>
#include <QMessageBox>
#include "mixersettings.h"
#include "systemsettings.h"
#include "actuatorsettings.h"
#include "actuatorcommand.h"
//#define Pi 3.14159265358979323846
/**
Helper function to setup the UI
Constructor
*/
void ConfigVehicleTypeWidget::setupMultiRotorUI(QString frameType)
ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent)
{
if (frameType == "Tri" || frameType == "Tricopter Y") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Tricopter Y"));
m_aircraft = aircraft;
}
/**
Destructor
*/
ConfigMultiRotorWidget::~ConfigMultiRotorWidget()
{
// Do nothing
}
void ConfigMultiRotorWidget::setupUI(QString frameType)
{
Q_ASSERT(m_aircraft);
Q_ASSERT(uiowner);
Q_ASSERT(quad);
int i;
// set aircraftType to Multirotor, disable triyaw channel
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->triYawChannelBox->setEnabled(false);
// disable all motor channel boxes
for (i=1; i <=8; i++) {
// do it manually so we can turn off any error decorations
QComboBox *combobox = qFindChild<QComboBox*>(uiowner, "multiMotorChannelBox" + QString::number(i));
if (combobox) {
combobox->setEnabled(false);
combobox->setItemData(0, 0, Qt::DecorationRole);
}
}
if (frameType == "Tri" || frameType == "Tricopter Y") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y"));
quad->setElementId("tri");
//Enable all necessary motor channel boxes...
for (int i=1; i <=3; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
}
//and grey out all unused motor channel boxes
for (int i=4; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(false);
for (i=1; i <=3; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
m_aircraft->triYawChannelBox->setEnabled(true);
} else if (frameType == "QuadX" || frameType == "Quad X") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Quad X"));
m_aircraft->triYawChannelBox->setEnabled(true);
}
else if (frameType == "QuadX" || frameType == "Quad X") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X"));
quad->setElementId("quad-X");
//Enable all necessary motor channel boxes...
for (int i=1; i <=4; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (i=1; i <=4; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
//and grey out all unused motor channel boxes
for (int i=5; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(false);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50);
} else if (frameType == "QuadP" || frameType == "Quad +") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Quad +"));
}
else if (frameType == "QuadP" || frameType == "Quad +") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +"));
quad->setElementId("quad-plus");
//Enable all necessary motor channel boxes...
for (int i=1; i <=4; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
}
//and grey out all unused motor channel boxes
for (int i=5; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(false);
for (i=1; i <=4; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50);
} else if (frameType == "Hexa" || frameType == "Hexacopter") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Hexacopter"));
}
else if (frameType == "Hexa" || frameType == "Hexacopter")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter"));
quad->setElementId("quad-hexa");
//Enable all necessary motor channel boxes...
for (int i=1; i <=6; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (i=1; i <=6; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
//and grey out all unused motor channel boxes
for (int i=7; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(false);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(33);
} else if (frameType == "HexaX" || frameType == "Hexacopter X" ) {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Hexacopter X"));
}
else if (frameType == "HexaX" || frameType == "Hexacopter X" ) {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X"));
quad->setElementId("quad-hexa-H");
//Enable all necessary motor channel boxes...
for (int i=1; i <=6; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (i=1; i <=6; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
//and grey out all unused motor channel boxes
for (int i=7; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(false);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(33);
} else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Hexacopter Y6"));
}
else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6"));
quad->setElementId("hexa-coax");
//Enable all necessary motor channel boxes...
for (int i=1; i <=6; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (i=1; i <=6; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
//and grey out all unused motor channel boxes
for (int i=7; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(false);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(66);
} else if (frameType == "Octo" || frameType == "Octocopter") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octocopter"));
}
else if (frameType == "Octo" || frameType == "Octocopter")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter"));
quad->setElementId("quad-octo");
//Enable all necessary motor channel boxes
for (int i=1; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(25);
} else if (frameType == "OctoV" || frameType == "Octocopter V") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octocopter V"));
}
else if (frameType == "OctoV" || frameType == "Octocopter V")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V"));
quad->setElementId("quad-octo-v");
//Enable all necessary motor channel boxes
for (int i=1; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(25);
m_aircraft->mrPitchMixLevel->setValue(25);
m_aircraft->mrYawMixLevel->setValue(25);
} else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octo Coax +"));
}
else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +"));
quad->setElementId("octo-coax-P");
//Enable all necessary motor channel boxes
for (int i=1; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (int i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50);
} else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Octo Coax X"));
}
else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X"));
quad->setElementId("octo-coax-X");
//Enable all necessary motor channel boxes
for (int i=1; i <=8; i++) {
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i));
combobox->setEnabled(true);
for (int i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
m_aircraft->triYawChannelBox->setEnabled(false);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50);
@ -235,12 +226,61 @@ void ConfigVehicleTypeWidget::setupMultiRotorUI(QString frameType)
}
}
void ConfigMultiRotorWidget::ResetActuators(GUIConfigDataUnion* configData)
{
configData->multi.VTOLMotorN = 0;
configData->multi.VTOLMotorNE = 0;
configData->multi.VTOLMotorE = 0;
configData->multi.VTOLMotorSE = 0;
configData->multi.VTOLMotorS = 0;
configData->multi.VTOLMotorSW = 0;
configData->multi.VTOLMotorW = 0;
configData->multi.VTOLMotorNW = 0;
configData->multi.TRIYaw = 0;
}
QStringList ConfigMultiRotorWidget::getChannelDescriptions()
{
int i;
QStringList channelDesc;
// init a channel_numelem list of channel desc defaults
for (i=0; i < (int)(ConfigMultiRotorWidget::CHANNEL_NUMELEM); i++)
{
channelDesc.append(QString("-"));
}
// get the gui config data
GUIConfigDataUnion configData = GetConfigData();
multiGUISettingsStruct multi = configData.multi;
if (multi.VTOLMotorN > 0 && multi.VTOLMotorN < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorN-1] = QString("VTOLMotorN");
if (multi.VTOLMotorNE > 0 && multi.VTOLMotorNE < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorNE-1] = QString("VTOLMotorNE");
if (multi.VTOLMotorNW > 0 && multi.VTOLMotorNW < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorNW-1] = QString("VTOLMotorNW");
if (multi.VTOLMotorS > 0 && multi.VTOLMotorS < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorS-1] = QString("VTOLMotorS");
if (multi.VTOLMotorSE > 0 && multi.VTOLMotorSE < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorSE-1] = QString("VTOLMotorSE");
if (multi.VTOLMotorSW > 0 && multi.VTOLMotorSW < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorSW-1] = QString("VTOLMotorSW");
if (multi.VTOLMotorW > 0 && multi.VTOLMotorW < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorW-1] = QString("VTOLMotorW");
if (multi.VTOLMotorE > 0 && multi.VTOLMotorE < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorE-1] = QString("VTOLMotorE");
return channelDesc;
}
/**
Helper function to update the UI widget objects
*/
QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
{
QString airframeType;
QList<QString> motorList;
@ -279,7 +319,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
airframeType = "HexaCoax";
//Show any config errors in GUI
throwMultiRotorChannelConfigError(6);
throwConfigError(6);
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
@ -313,7 +353,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
airframeType = "Octo";
//Show any config errors in GUI
throwMultiRotorChannelConfigError(8);
throwConfigError(8);
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
@ -348,7 +388,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
airframeType = "OctoV";
//Show any config errors in GUI
throwMultiRotorChannelConfigError(8);
throwConfigError(8);
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
@ -384,7 +424,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
airframeType = "OctoCoaxP";
//Show any config errors in GUI
throwMultiRotorChannelConfigError(8);
throwConfigError(8);
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
@ -419,7 +459,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
airframeType = "OctoCoaxX";
//Show any config errors in GUI
throwMultiRotorChannelConfigError(8);
throwConfigError(8);
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
@ -454,7 +494,7 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
airframeType = "Tri";
//Show any config errors in GUI
throwMultiRotorChannelConfigError(3);
throwConfigError(3);
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
m_aircraft->multiMotorChannelBox2->currentText() == "None" ||
m_aircraft->multiMotorChannelBox3->currentText() == "None" ) {
@ -467,10 +507,11 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
}
motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS";
setupMotors(motorList);
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
field = obj->getField("FixedWingYaw1");
field->setValue(m_aircraft->triYawChannelBox->currentText());
GUIConfigDataUnion config = GetConfigData();
config.multi.TRIYaw = m_aircraft->triYawChannelBox->currentIndex();
SetConfigData(config);
// Motor 1 to 6, Y6 Layout:
// pitch roll yaw
@ -485,21 +526,20 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
{ 0, 0, 0}
};
setupMultiRotorMixer(mixer);
int tmpVal = m_aircraft->triYawChannelBox->currentIndex()-1;
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
field = obj->getField(mixerTypes.at(tmpVal));
field->setValue("Servo");
field = obj->getField(mixerVectors.at(tmpVal));
resetField(field);
int ti = field->getElementNames().indexOf("Yaw");
field->setValue(127,ti);
//tell the mixer about tricopter yaw channel
UAVDataObject* mixerObj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixerObj);
int channel = m_aircraft->triYawChannelBox->currentIndex()-1;
if (channel > -1){
setMixerType(mixerObj, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixerObj, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
}
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
}
// Now reflect those settings in the "Custom" panel as well
updateCustomAirframeUI();
}
return airframeType;
}
@ -509,342 +549,253 @@ QString ConfigVehicleTypeWidget::updateMultiRotorObjectsFromWidgets()
/**
Helper function to refresh the UI widget values
*/
void ConfigVehicleTypeWidget::refreshMultiRotorWidgetsValues(QString frameType)
void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
{
//////////////////////////////////////////////////////////////////
// Retrieve settings
//////////////////////////////////////////////////////////////////
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
UAVObjectField *field;
int channel;
double value;
GUIConfigDataUnion config = GetConfigData();
multiGUISettingsStruct multi = config.multi;
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
if (frameType == "QuadP") {
// Motors 1/2/3/4 are: N / E / S / W
field = obj->getField(QString("VTOLMotorN"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorS"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
// Motors 1/2/3/4 are: N / E / S / W
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorW);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = field->getDouble(i)/1.27;
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = (1-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1;
field = obj->getField(mixerVectors.at(tmpVal));
i = field->getElementNames().indexOf("Roll");
val = -field->getDouble(i)/1.27;
m_aircraft->mrRollMixLevel->setValue(val);
}
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 );
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( -value/1.27);
}
} else if (frameType == "QuadX") {
// Motors 1/2/3/4 are: NW / NE / SE / SW
field = obj->getField(QString("VTOLMotorNW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = field->getDouble(i)/1.27;
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = 1-field->getDouble(i)/1.27;
m_aircraft->mrYawMixLevel->setValue(val);
i = field->getElementNames().indexOf("Roll");
val = field->getDouble(i)/1.27;
m_aircraft->mrRollMixLevel->setValue(val);
}
// Motors 1/2/3/4 are: NW / NE / SE / SW
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorSE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorSW);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( value/1.27);
}
} else if (frameType == "Hexa") {
// Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW
field = obj->getField(QString("VTOLMotorN"));
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNE"));
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSE"));
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorS"));
m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSW"));
m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNW"));
m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = floor(field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1;
if(tmpVal>-1)
{
field = obj->getField(mixerVectors.at(tmpVal));
i = field->getElementNames().indexOf("Roll");
val = floor(1-field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
}
}
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorSE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorSW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorNW);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) );
//change channels
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) );
}
} else if (frameType == "HexaX") {
// Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW
field = obj->getField(QString("VTOLMotorNE"));
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorE"));
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSE"));
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSW"));
m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorW"));
m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNW"));
m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = floor(field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1;
field = obj->getField(mixerVectors.at(tmpVal));
i = field->getElementNames().indexOf("Roll");
val = floor(1-field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
}
// Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorSE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorSW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorNW);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) );
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) );
}
} else if (frameType == "HexaCoax") {
// Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE
field = obj->getField(QString("VTOLMotorNW"));
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorW"));
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNE"));
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorE"));
m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorS"));
m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSE"));
m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = floor(2*field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
i = field->getElementNames().indexOf("Roll");
val = floor(field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
}
// Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorNE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorSE);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( value/1.27 );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( value/1.27 );
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( value/1.27);
}
} else if (frameType == "Octo" || frameType == "OctoV" ||
frameType == "OctoCoaxP") {
// Motors 1 to 8 are N / NE / E / etc
field = obj->getField(QString("VTOLMotorN"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorS"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox7->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox8->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
if (frameType == "Octo") {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = floor(field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1;
field = obj->getField(mixerVectors.at(tmpVal));
i = field->getElementNames().indexOf("Roll");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
} else if (frameType == "OctoV") {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Yaw");
double val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
i = field->getElementNames().indexOf("Roll");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
tmpVal = m_aircraft->multiMotorChannelBox2->currentIndex()-1;
field = obj->getField(mixerVectors.at(tmpVal));
i = field->getElementNames().indexOf("Pitch");
val = floor(field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
} else if (frameType == "OctoCoaxP") {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = floor(field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
tmpVal = m_aircraft->multiMotorChannelBox3->currentIndex()-1;
field = obj->getField(mixerVectors.at(tmpVal));
i = field->getElementNames().indexOf("Roll");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
}
}
// Motors 1 to 8 are N / NE / E / etc
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorSE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorSW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox7,multi.VTOLMotorW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox8,multi.VTOLMotorNW);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
if (frameType == "Octo") {
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) );
//change channels
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) );
}
else if (frameType == "OctoV") {
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) );
//change channels
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) );
}
else if (frameType == "OctoCoaxP") {
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) );
//change channels
channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1;
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) );
}
}
} else if (frameType == "OctoCoaxX") {
// Motors 1 to 8 are N / NE / E / etc
field = obj->getField(QString("VTOLMotorNW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorN"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox4->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox5->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorS"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox6->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorSW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox7->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox8->setCurrentIndex(m_aircraft->multiMotorChannelBox4->findText(field->getValue().toString()));
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = floor(field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Yaw");
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
i = field->getElementNames().indexOf("Roll");
val = floor(field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
}
// Motors 1 to 8 are N / NE / E / etc
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorN);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorNE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5,multi.VTOLMotorSE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox7,multi.VTOLMotorSW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox8,multi.VTOLMotorW);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) );
}
} else if (frameType == "Tri") {
// Motors 1 to 8 are N / NE / E / etc
field = obj->getField(QString("VTOLMotorNW"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox1->setCurrentIndex(m_aircraft->multiMotorChannelBox1->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorNE"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox2->setCurrentIndex(m_aircraft->multiMotorChannelBox2->findText(field->getValue().toString()));
field = obj->getField(QString("VTOLMotorS"));
Q_ASSERT(field);
m_aircraft->multiMotorChannelBox3->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
field = obj->getField(QString("FixedWingYaw1"));
Q_ASSERT(field);
m_aircraft->triYawChannelBox->setCurrentIndex(m_aircraft->multiMotorChannelBox3->findText(field->getValue().toString()));
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
int tmpVal= m_aircraft->multiMotorChannelBox1->currentIndex()-1;
// tmpVal will be -1 if value is set to "None"
if (tmpVal > -1) {
field = obj->getField(mixerVectors.at(tmpVal));
int i = field->getElementNames().indexOf("Pitch");
double val = floor(2*field->getDouble(i)/1.27);
m_aircraft->mrPitchMixLevel->setValue(val);
i = field->getElementNames().indexOf("Roll");
val = floor(field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
}
// Motors 1 to 8 are N / NE / E / etc
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->triYawChannelBox,multi.TRIYaw);
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
{
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
m_aircraft->mrPitchMixLevel->setValue( floor(2*value/1.27) );
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) );
}
}
}
@ -853,27 +804,20 @@ void ConfigVehicleTypeWidget::refreshMultiRotorWidgetsValues(QString frameType)
/**
Helper function: setupQuadMotor
*/
void ConfigVehicleTypeWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw)
void ConfigMultiRotorWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw)
{
qDebug()<<QString("Setup quad motor channel=%0 pitch=%1 roll=%2 yaw=%3").arg(channel).arg(pitch).arg(roll).arg(yaw);
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
UAVObjectField *field = obj->getField(mixerTypes.at(channel));
field->setValue("Motor");
field = obj->getField(mixerVectors.at(channel));
// First of all reset the vector
resetField(field);
int ti = field->getElementNames().indexOf("ThrottleCurve1");
field->setValue(127, ti);
ti = field->getElementNames().indexOf("Roll");
field->setValue(roll*127,ti);
qDebug()<<"Set roll="<<roll*127;
ti = field->getElementNames().indexOf("Pitch");
field->setValue(pitch*127,ti);
qDebug()<<"Set pitch="<<pitch*127;
ti = field->getElementNames().indexOf("Yaw");
field->setValue(yaw*127,ti);
qDebug()<<"Set yaw="<<yaw*127;
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 0);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, roll*127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch*127);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, yaw*127);
}
@ -881,21 +825,42 @@ void ConfigVehicleTypeWidget::setupQuadMotor(int channel, double pitch, double r
/**
Helper function: setup motors. Takes a list of channel names in input.
*/
void ConfigVehicleTypeWidget::setupMotors(QList<QString> motorList)
void ConfigMultiRotorWidget::setupMotors(QList<QString> motorList)
{
resetActuators();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
UAVObjectField *field;
QList<QComboBox*> mmList;
mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3
<< m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6
<< m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8;
GUIConfigDataUnion configData = GetConfigData();
ResetActuators(&configData);
int index;
foreach (QString motor, motorList) {
field = obj->getField(motor);
field->setValue(mmList.takeFirst()->currentText());
index = mmList.takeFirst()->currentIndex();
//qDebug()<<QString("Setup motor: %0 = %1").arg(motor).arg(index);
if (motor == QString("VTOLMotorN"))
configData.multi.VTOLMotorN = index;
else if (motor == QString("VTOLMotorNE"))
configData.multi.VTOLMotorNE = index;
else if (motor == QString("VTOLMotorE"))
configData.multi.VTOLMotorE = index;
else if (motor == QString("VTOLMotorSE"))
configData.multi.VTOLMotorSE = index;
else if (motor == QString( "VTOLMotorS"))
configData.multi.VTOLMotorS = index;
else if (motor == QString( "VTOLMotorSW"))
configData.multi.VTOLMotorSW = index;
else if (motor == QString( "VTOLMotorW"))
configData.multi.VTOLMotorW = index;
else if (motor == QString( "VTOLMotorNW"))
configData.multi.VTOLMotorNW = index;
}
//obj->updated(); // Save...
SetConfigData(configData);
}
@ -903,12 +868,12 @@ void ConfigVehicleTypeWidget::setupMotors(QList<QString> motorList)
/**
Set up a Quad-X or Quad-P mixer
*/
bool ConfigVehicleTypeWidget::setupQuad(bool pLayout)
bool ConfigMultiRotorWidget::setupQuad(bool pLayout)
{
// Check coherence:
//Show any config errors in GUI
throwMultiRotorChannelConfigError(4);
throwConfigError(4);
// - Four engines have to be defined
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
@ -979,11 +944,11 @@ bool ConfigVehicleTypeWidget::setupQuad(bool pLayout)
/**
Set up a Hexa-X or Hexa-P mixer
*/
bool ConfigVehicleTypeWidget::setupHexa(bool pLayout)
bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
{
// Check coherence:
//Show any config errors in GUI
throwMultiRotorChannelConfigError(6);
throwConfigError(6);
// - Four engines have to be defined
if (m_aircraft->multiMotorChannelBox1->currentText() == "None" ||
@ -1060,7 +1025,7 @@ bool ConfigVehicleTypeWidget::setupHexa(bool pLayout)
/**
This function sets up the multirotor mixer values.
*/
bool ConfigVehicleTypeWidget::setupMultiRotorMixer(double mixerFactors[8][3])
bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
{
qDebug()<<"Mixer factors";
qDebug()<<mixerFactors[0][0]<<" "<<mixerFactors[0][1]<<" "<<mixerFactors[0][2];
@ -1107,34 +1072,25 @@ bool ConfigVehicleTypeWidget::setupMultiRotorMixer(double mixerFactors[8][3])
/**
This function displays text and color formatting in order to help the user understand what channels have not yet been configured.
*/
void ConfigVehicleTypeWidget::throwMultiRotorChannelConfigError(int numMotors)
{
void ConfigMultiRotorWidget::throwConfigError(int numMotors)
{
//Initialize configuration error flag
bool error=false;
//Iterate through all instances of multiMotorChannelBox
for (int i=0; i<numMotors; i++) {
//Fine widgets with text "multiMotorChannelBox.x", where x is an integer
QComboBox *combobox = qFindChild<QComboBox*>(this, "multiMotorChannelBox" + QString::number(i+1));
if (combobox){ //if QLabel exists
QLabel *label = qFindChild<QLabel*>(this, "MotorOutputLabel" + QString::number(i+1));
if (combobox->currentText() == "None") {
// label->setText("<font color='red'>" + label->text() + "</font>");
QComboBox *combobox = qFindChild<QComboBox*>(uiowner, "multiMotorChannelBox" + QString::number(i+1));
if (combobox){
if (combobox->currentText() == "None") {
int size = combobox->style()->pixelMetric(QStyle::PM_SmallIconSize);
QPixmap pixmap(size,size);
pixmap.fill(QColor("red"));
combobox->setItemData(0, pixmap, Qt::DecorationRole);//Set color palettes
// combobox->setStyleSheet("QComboBox { color: red}");
combobox->setItemData(0, pixmap, Qt::DecorationRole);//Set color palettes
error=true;
}
else {
combobox->setItemData(0, 0, Qt::DecorationRole);//Reset color palettes
// combobox->setStyleSheet("color: black;");
// QTextEdit* htmlText=new QTextEdit(label->text()); // htmlText is any QString with html tags.
// label->setText(htmlText->toPlainText());
combobox->setItemData(0, 0, Qt::DecorationRole);//Reset color palettes
}
}
}
@ -1143,4 +1099,6 @@ void ConfigVehicleTypeWidget::throwMultiRotorChannelConfigError(int numMotors)
if (error){
m_aircraft->mrStatusLabel->setText(QString("<font color='red'>ERROR: Assign all %1 motor channels</font>").arg(numMotors));
}
}
}

View File

@ -0,0 +1,84 @@
/**
******************************************************************************
*
* @file configairframetwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief Airframe configuration panel
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CONFIGMULTIROTORWIDGET_H
#define CONFIGMULTIROTORWIDGET_H
#include "ui_airframe.h"
#include "../uavobjectwidgetutils/configtaskwidget.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
#include "uavtalk/telemetrymanager.h"
#include <QtGui/QWidget>
#include <QList>
#include <QItemDelegate>
class Ui_Widget;
class ConfigMultiRotorWidget: public VehicleConfig
{
Q_OBJECT
public:
ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft = 0, QWidget *parent = 0);
~ConfigMultiRotorWidget();
friend class ConfigVehicleTypeWidget;
private:
Ui_AircraftWidget *m_aircraft;
QWidget *uiowner;
QGraphicsSvgItem *quad;
bool setupQuad(bool pLayout);
bool setupHexa(bool pLayout);
bool setupOcto();
bool setupMultiRotorMixer(double mixerFactors[8][3]);
void setupMotors(QList<QString> motorList);
void setupQuadMotor(int channel, double roll, double pitch, double yaw);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
private slots:
virtual void setupUI(QString airframeType);
virtual void refreshWidgetsValues(QString frameType);
virtual QString updateConfigObjectsFromWidgets();
void throwConfigError(int numMotors);
protected:
signals:
void configurationChanged();
};
#endif // CONFIGMULTIROTORWIDGET_H

View File

@ -0,0 +1,256 @@
/**
******************************************************************************
*
* @file vehicleconfig.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief bit storage of config ui settings
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "cfg_vehicletypes/vehicleconfig.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
#include "systemsettings.h"
#include <QDebug>
VehicleConfig::VehicleConfig(QWidget *parent) : ConfigTaskWidget(parent)
{
//Generate lists of mixerTypeNames, mixerVectorNames, channelNames
channelNames << "None";
for (int i = 0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++) {
mixerTypes << QString("Mixer%1Type").arg(i+1);
mixerVectors << QString("Mixer%1Vector").arg(i+1);
channelNames << QString("Channel%1").arg(i+1);
}
// typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2,
//MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5,
//MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8,
//MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem;
mixerTypeDescriptions << "Disabled" << "Motor" << "Servo" << "CameraRoll" << "CameraPitch"
<< "CameraYaw" << "Accessory0" << "Accessory1" << "Accessory2"
<< "Accessory3" << "Accessory4" << "Accessory5";
// This is needed because new style tries to compact things as much as possible in grid
// and on OSX the widget sizes of PushButtons is reported incorrectly:
// https://bugreports.qt-project.org/browse/QTBUG-14591
foreach( QPushButton * btn, findChildren<QPushButton*>() ) {
btn->setAttribute(Qt::WA_LayoutUsesWidgetRect);
}
}
VehicleConfig::~VehicleConfig()
{
// Do nothing
}
GUIConfigDataUnion VehicleConfig::GetConfigData() {
int i;
GUIConfigDataUnion configData;
// get an instance of systemsettings
SystemSettings * systemSettings = SystemSettings::GetInstance(getUAVObjectManager());
Q_ASSERT(systemSettings);
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
// copy systemsettings -> local configData
for(i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++)
configData.UAVObject[i]=systemSettingsData.GUIConfigData[i];
// sanity check
Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM ==
(sizeof(configData.UAVObject) / sizeof(configData.UAVObject[0])));
return configData;
}
void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) {
int i;
// sanity check
Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM ==
(sizeof(configData.UAVObject) / sizeof(configData.UAVObject[0])));
// get an instance of systemsettings
SystemSettings * systemSettings = SystemSettings::GetInstance(getUAVObjectManager());
Q_ASSERT(systemSettings);
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
// copy parameter configData -> systemsettings
for (i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++)
systemSettingsData.GUIConfigData[i] = configData.UAVObject[i];
systemSettings->setData(systemSettingsData);
systemSettings->updated();
//emit ConfigurationChanged();
}
void VehicleConfig::ResetActuators(GUIConfigDataUnion* configData)
{
}
QStringList VehicleConfig::getChannelDescriptions()
{
QStringList channelDesc;
// init a channel_numelem list of channel desc defaults
for (int i=0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++)
{
channelDesc.append(QString("-"));
}
return channelDesc;
}
/**
Helper function:
Sets the current index on supplied combobox to index
if it is within bounds 0 <= index < combobox.count()
*/
void VehicleConfig::setComboCurrentIndex(QComboBox* box, int index)
{
Q_ASSERT(box);
if (index >= 0 && index < box->count())
box->setCurrentIndex(index);
}
/**
Helper function:
enables/disables the named combobox within supplied uiowner
*/
void VehicleConfig::enableComboBox(QWidget* owner, QString boxName, bool enable)
{
QComboBox* box = qFindChild<QComboBox*>(owner, boxName);
if (box)
box->setEnabled(enable);
}
QString VehicleConfig::getMixerType(UAVDataObject* mixer, int channel)
{
Q_ASSERT(mixer);
QString mixerType = mixerTypeDescriptions[0]; //default to disabled
if (channel >= 0 && channel < mixerTypes.count()) {
UAVObjectField *field = mixer->getField(mixerTypes.at(channel));
Q_ASSERT(field);
if (field)
mixerType = field->getValue().toString();
}
return mixerType;
}
void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType)
{
Q_ASSERT(mixer);
qDebug() << QString("setMixerType channel %0, type %1").arg(channel).arg(mixerType);
if (channel >= 0 && channel < mixerTypes.count()) {
UAVObjectField *field = mixer->getField(mixerTypes.at(channel));
Q_ASSERT(field);
if (field) {
if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count())
{
field->setValue(mixerTypeDescriptions[mixerType]);
mixer->updated();
}
}
}
}
void VehicleConfig::resetMixerVector(UAVDataObject* mixer, int channel)
{
Q_ASSERT(mixer);
if (channel >= 0 && channel < mixerVectors.count()) {
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 0);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 0);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 0);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 0);
setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 0);
}
}
double VehicleConfig::getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName)
{
Q_ASSERT(mixer);
double value = 0;
if (channel >= 0 && channel < mixerVectors.count()) {
UAVObjectField *field = mixer->getField(mixerVectors.at(channel));
Q_ASSERT(field);
if (field) {
value = field->getDouble(elementName);
}
}
return value;
}
void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName, double value)
{
Q_ASSERT(mixer);
qDebug() << QString("setMixerVectorValue channel %0, name %1, value %2").arg(channel).arg(elementName).arg(value);
if (channel >= 0 && channel < mixerVectors.count()) {
UAVObjectField *field = mixer->getField(mixerVectors.at(channel));
Q_ASSERT(field);
if (field) {
field->setDouble(value, elementName);
mixer->updated();
}
}
}
/**
Reset the contents of a field
*/
void VehicleConfig::resetField(UAVObjectField * field)
{
for (unsigned int i=0;i<field->getNumElements();i++) {
field->setValue(0,i);
}
}
/**
* Util function to get a pointer to the object manager
* @return pointer to the UAVObjectManager
*/
UAVObjectManager* VehicleConfig::getUAVObjectManager() {
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>();
Q_ASSERT(objMngr);
return objMngr;
}

View File

@ -0,0 +1,156 @@
/**
******************************************************************************
*
* @file vehicleconfig.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief bit storage of config ui settings
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef GUIVEHICLECONFIG_H
#define GUIVEHICLECONFIG_H
#include "../uavobjectwidgetutils/configtaskwidget.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
typedef struct {
uint VTOLMotorN:4;
uint VTOLMotorS:4;
uint VTOLMotorE:4;
uint VTOLMotorW:4;
uint VTOLMotorNW:4;
uint VTOLMotorNE:4;
uint VTOLMotorSW:4;
uint VTOLMotorSE:4; //32bits
uint TRIYaw:4;
quint32 padding:28; //64bits
quint32 padding1;
quint32 padding2; //128bits
} __attribute__((packed)) multiGUISettingsStruct;
typedef struct {
uint SwashplateType:3;
uint FirstServoIndex:2;
uint CorrectionAngle:9;
uint ccpmCollectivePassthroughState:1;
uint ccpmLinkCyclicState:1;
uint ccpmLinkRollState:1;
uint SliderValue0:7;
uint SliderValue1:7;
uint SliderValue2:7;//41bits
uint ServoIndexW:4;
uint ServoIndexX:4;
uint ServoIndexY:4;
uint ServoIndexZ:4;//57bits
uint Throttle:4;
uint Tail:4; //65bits
quint32 padding:31; //96bits
quint32 padding1; //128bits
} __attribute__((packed)) heliGUISettingsStruct;
typedef struct {
uint FixedWingThrottle:4;
uint FixedWingRoll1:4;
uint FixedWingRoll2:4;
uint FixedWingPitch1:4;
uint FixedWingPitch2:4;
uint FixedWingYaw1:4;
uint FixedWingYaw2:4;
uint padding:4; //32bits
quint32 padding1;
quint32 padding2;
quint32 padding3; //128bits
} __attribute__((packed)) fixedGUISettingsStruct;
typedef struct {
uint GroundVehicleThrottle1:4;
uint GroundVehicleThrottle2:4;
uint GroundVehicleSteering1:4;
uint GroundVehicleSteering2:4;
uint padding:16; //32bits
quint32 padding1;
quint32 padding2;
quint32 padding3; //128bits
} __attribute__((packed)) groundGUISettingsStruct;
typedef union
{
uint UAVObject[4]; //32bits * 4
heliGUISettingsStruct heli; //128bits
fixedGUISettingsStruct fixedwing;
multiGUISettingsStruct multi;
groundGUISettingsStruct ground;
} GUIConfigDataUnion;
class VehicleConfig: public ConfigTaskWidget
{
Q_OBJECT
public:
VehicleConfig(QWidget *parent = 0);
~VehicleConfig();
/* Enumeration options for field MixerType */
typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2, MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5, MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8, MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem;
/* Array element names for field MixerVector */
typedef enum { MIXERVECTOR_THROTTLECURVE1=0, MIXERVECTOR_THROTTLECURVE2=1, MIXERVECTOR_ROLL=2, MIXERVECTOR_PITCH=3, MIXERVECTOR_YAW=4 } MixerVectorElem;
static GUIConfigDataUnion GetConfigData();
static void SetConfigData(GUIConfigDataUnion configData);
static void resetField(UAVObjectField * field);
static void setComboCurrentIndex(QComboBox* box, int index);
static void enableComboBox(QWidget* owner, QString boxName, bool enable);
double getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName);
void setMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName, double value);
void resetMixerVector(UAVDataObject* mixer, int channel);
QString getMixerType(UAVDataObject* mixer, int channel);
void setMixerType(UAVDataObject* mixer, int channel, MixerTypeElem mixerType);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
QStringList channelNames;
QStringList mixerTypes;
QStringList mixerVectors;
QStringList mixerTypeDescriptions;
static const quint32 CHANNEL_NUMELEM = 10;
private:
static UAVObjectManager* getUAVObjectManager();
private slots:
public slots:
signals:
//void ConfigurationChanged();
protected:
};
#endif // GUIVEHICLECONFIG_H

View File

@ -30,7 +30,11 @@ HEADERS += configplugin.h \
inputchannelform.h \
configcamerastabilizationwidget.h \
configtxpidwidget.h \
outputchannelform.h \
outputchannelform.h \
cfg_vehicletypes/configmultirotorwidget.h \
cfg_vehicletypes/configgroundvehiclewidget.h \
cfg_vehicletypes/configfixedwingwidget.h \
cfg_vehicletypes/vehicleconfig.h \
configrevowidget.h \
config_global.h
SOURCES += configplugin.cpp \
@ -62,7 +66,8 @@ SOURCES += configplugin.cpp \
cfg_vehicletypes/configgroundvehiclewidget.cpp \
cfg_vehicletypes/configfixedwingwidget.cpp \
cfg_vehicletypes/configccpmwidget.cpp \
outputchannelform.cpp
outputchannelform.cpp \
cfg_vehicletypes/vehicleconfig.cpp
FORMS += airframe.ui \
cc_hw_settings.ui \
pro_hw_settings.ui \

View File

@ -33,8 +33,8 @@
#include <QDebug>
#include <QDesktopServices>
#include <QUrl>
#include <accels.h>
#include <gyros.h>
#include "accels.h"
#include "gyros.h"
ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
ConfigTaskWidget(parent),
@ -107,7 +107,6 @@ void ConfigCCAttitudeWidget::accelsUpdated(UAVObject * obj) {
attitudeSettingsData.GyroBias[2] = -z_gyro_bias;
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE;
AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData);
} else {
// Possible to get here if weird threading stuff happens. Just ignore updates.
qDebug("Unexpected accel update received.");
@ -174,3 +173,10 @@ void ConfigCCAttitudeWidget::enableControls(bool enable)
ConfigTaskWidget::enableControls(enable);
}
void ConfigCCAttitudeWidget::updateObjectsFromWidgets()
{
ConfigTaskWidget::updateObjectsFromWidgets();
ui->zeroBiasProgress->setValue(0);
}

View File

@ -46,6 +46,8 @@ public:
explicit ConfigCCAttitudeWidget(QWidget *parent = 0);
~ConfigCCAttitudeWidget();
virtual void updateObjectsFromWidgets();
private slots:
void accelsUpdated(UAVObject * obj);
void timeout();

View File

@ -90,9 +90,6 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
qwd = new ConfigTxPIDWidget(this);
ftw->insertTab(ConfigGadgetWidget::txpid, qwd, QIcon(":/configgadget/images/txpid.png"), QString("TxPID"));
qwd = new ConfigPipXtremeWidget(this);
ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme"));
// *********************
// Listen to autopilot connection events
@ -108,6 +105,19 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
help = 0;
connect(ftw,SIGNAL(currentAboutToShow(int,bool*)),this,SLOT(tabAboutToChange(int,bool*)));//,Qt::BlockingQueuedConnection);
// Connect to the PipXStatus object updates
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
pipxStatusObj = dynamic_cast<UAVDataObject*>(objManager->getObject("PipXStatus"));
if (pipxStatusObj != NULL ) {
connect(pipxStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updatePipXStatus(UAVObject*)));
} else {
qDebug() << "Error: Object is unknown (PipXStatus).";
}
// Create the timer that is used to timeout the connection to the PipX.
pipxTimeout = new QTimer(this);
connect(pipxTimeout, SIGNAL(timeout()),this,SLOT(onPipxtremeDisconnect()));
pipxConnected = false;
}
ConfigGadgetWidget::~ConfigGadgetWidget()
@ -203,5 +213,27 @@ void ConfigGadgetWidget::tabAboutToChange(int i,bool * proceed)
}
}
/*!
\brief Called by updates to @PipXStatus
*/
void ConfigGadgetWidget::updatePipXStatus(UAVObject *object)
{
// Restart the disconnection timer.
pipxTimeout->start(5000);
if (!pipxConnected)
{
qDebug()<<"ConfigGadgetWidget onPipxtremeConnect";
QWidget *qwd = new ConfigPipXtremeWidget(this);
ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme"));
ftw->setCurrentIndex(ConfigGadgetWidget::pipxtreme);
pipxConnected = true;
}
}
void ConfigGadgetWidget::onPipxtremeDisconnect() {
qDebug()<<"ConfigGadgetWidget onPipxtremeDisconnect";
pipxTimeout->stop();
ftw->removeTab(ConfigGadgetWidget::pipxtreme);
pipxConnected = false;
}

View File

@ -56,14 +56,25 @@ public slots:
void onAutopilotConnect();
void onAutopilotDisconnect();
void tabAboutToChange(int i,bool *);
void updatePipXStatus(UAVObject *object);
void onPipxtremeDisconnect();
signals:
void autopilotConnected();
void autopilotDisconnected();
void pipxtremeConnect();
void pipxtremeDisconnect();
protected:
void resizeEvent(QResizeEvent * event);
MyTabbedStackWidget *ftw;
private:
UAVDataObject* pipxStatusObj;
// A timer that timesout the connction to the PipX.
QTimer *pipxTimeout;
bool pipxConnected;
};
#endif // CONFIGGADGETWIDGET_H

View File

@ -27,6 +27,7 @@
#include "configoutputwidget.h"
#include "outputchannelform.h"
#include "configvehicletypewidget.h"
#include "uavtalk/telemetrymanager.h"
@ -39,9 +40,11 @@
#include <QMessageBox>
#include <QDesktopServices>
#include <QUrl>
#include "mixersettings.h"
#include "actuatorcommand.h"
#include "actuatorsettings.h"
#include "systemalarms.h"
#include "systemsettings.h"
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false)
@ -231,35 +234,35 @@ void ConfigOutputWidget::sendChannelTest(int index, int value)
/**
Request the current config from the board (RC Output)
*/
void ConfigOutputWidget::refreshOutputWidgetsValues(UAVObject *)
void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj)
{
// Reset all channel assignements:
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
{
outputChannelForm->setAssignment("-");
}
Q_UNUSED(obj);
// FIXME: Use static accessor method for retrieving channel assignments
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Q_ASSERT(pm);
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
Q_ASSERT(objManager);
// Get the channel assignements:
UAVDataObject * obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
QList<UAVObjectField*> fieldList = obj->getFields();
foreach (UAVObjectField* field, fieldList) {
if (field->getUnits().contains("channel")) {
assignOutputChannel(obj,field->getName());
}
}
bool dirty=isDirty();
// Get Actuator Settings
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
Q_ASSERT(actuatorSettings);
ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData();
// get channel descriptions
QStringList ChannelDesc = ConfigVehicleTypeWidget::getChannelDescriptions();
// Initialize output forms
QList<OutputChannelForm*> outputChannelForms = findChildren<OutputChannelForm*>();
foreach(OutputChannelForm *outputChannelForm, outputChannelForms)
{
outputChannelForm->setAssignment(ChannelDesc[outputChannelForm->index()]);
// init min,max,neutral
int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()];
int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()];
outputChannelForm->minmax(minValue, maxValue);
int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()];
outputChannelForm->neutral(neutral);
}
// Get the SpinWhileArmed setting
m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE);
@ -275,6 +278,8 @@ void ConfigOutputWidget::refreshOutputWidgetsValues(UAVObject *)
m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])));
m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])));
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Q_ASSERT(pm);
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
if (utilMngr) {
int board = utilMngr->getBoardModel();

View File

@ -33,6 +33,7 @@
#include "uavobjectmanager.h"
#include "uavobject.h"
#include "uavobjectutilmanager.h"
#include "cfg_vehicletypes/vehicleconfig.h"
#include <QtGui/QWidget>
#include <QList>
@ -57,8 +58,7 @@ private:
void assignChannel(UAVDataObject *obj, QString str);
void assignOutputChannel(UAVDataObject *obj, QString str);
OutputChannelForm* getOutputChannelForm(const int index) const;
OutputChannelForm* getOutputChannelForm(const int index) const;
int mccDataRate;
UAVObject::Metadata accInitialData;
@ -69,7 +69,7 @@ private:
private slots:
void stopTests();
void disableIfNotMe(UAVObject *obj);
void refreshOutputWidgetsValues(UAVObject * obj = NULL);
virtual void refreshWidgetsValues(UAVObject * obj=NULL);
void updateObjectsFromWidgets();
void runChannelTests(bool state);
void sendChannelTest(int index, int value);

View File

@ -76,6 +76,7 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
addUAVObjectToWidgetRelation("PipXStatus", "Errors", m_pipx->Errors);
addUAVObjectToWidgetRelation("PipXStatus", "UAVTalkErrors", m_pipx->UAVTalkErrors);
addUAVObjectToWidgetRelation("PipXStatus", "Resets", m_pipx->Resets);
addUAVObjectToWidgetRelation("PipXStatus", "Dropped", m_pipx->Dropped);
addUAVObjectToWidgetRelation("PipXStatus", "RXRate", m_pipx->RXRate);
addUAVObjectToWidgetRelation("PipXStatus", "TXRate", m_pipx->TXRate);
@ -85,21 +86,16 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
connect(m_pipx->PairSelect3, SIGNAL(toggled(bool)), this, SLOT(pair3Toggled(bool)));
connect(m_pipx->PairSelect4, SIGNAL(toggled(bool)), this, SLOT(pair4Toggled(bool)));
// Create the timer that is used to timeout the connection to the PipX.
timeOut = new QTimer(this);
connect(timeOut, SIGNAL(timeout()),this,SLOT(disconnected()));
//Add scroll bar when necessary
QScrollArea *scroll = new QScrollArea;
scroll->setWidget(m_pipx->frame_3);
m_pipx->verticalLayout_3->addWidget(scroll);
//Add scroll bar when necessary
QScrollArea *scroll = new QScrollArea;
scroll->setWidget(m_pipx->frame_3);
m_pipx->verticalLayout_3->addWidget(scroll);
// Request and update of the setting object.
settingsUpdated = false;
pipxSettingsObj->requestUpdate();
disableMouseWheelEvents();
//pipxSettingsObj->requestUpdate();
disableMouseWheelEvents();
}
ConfigPipXtremeWidget::~ConfigPipXtremeWidget()
@ -144,9 +140,6 @@ void ConfigPipXtremeWidget::saveSettings()
void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
{
// Restart the disconnection timer.
timeOut->start(10000);
// Request and update of the setting object if we haven't received it yet.
if (!settingsUpdated)
pipxSettingsObj->requestUpdate();
@ -185,11 +178,15 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
}
UAVObjectField* pairRssiField = object->getField("PairSignalStrengths");
if (pairRssiField) {
m_pipx->PairSignalStrength1->setValue(pairRssiField->getValue(0).toInt());
m_pipx->PairSignalStrength2->setValue(pairRssiField->getValue(1).toInt());
m_pipx->PairSignalStrength3->setValue(pairRssiField->getValue(2).toInt());
m_pipx->PairSignalStrength4->setValue(pairRssiField->getValue(3).toInt());
} else {
m_pipx->PairSignalStrengthBar1->setValue(pairRssiField->getValue(0).toInt());
m_pipx->PairSignalStrengthBar2->setValue(pairRssiField->getValue(1).toInt());
m_pipx->PairSignalStrengthBar3->setValue(pairRssiField->getValue(2).toInt());
m_pipx->PairSignalStrengthBar4->setValue(pairRssiField->getValue(3).toInt());
m_pipx->PairSignalStrengthLabel1->setText(QString("%1dB").arg(pairRssiField->getValue(0).toInt()));
m_pipx->PairSignalStrengthLabel2->setText(QString("%1dB").arg(pairRssiField->getValue(1).toInt()));
m_pipx->PairSignalStrengthLabel3->setText(QString("%1dB").arg(pairRssiField->getValue(2).toInt()));
m_pipx->PairSignalStrengthLabel4->setText(QString("%1dB").arg(pairRssiField->getValue(3).toInt()));
} else {
qDebug() << "PipXtremeGadgetWidget: Count not read PairID field.";
}
@ -262,14 +259,20 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
*/
void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
{
settingsUpdated = true;
enableControls(true);
if (!settingsUpdated)
{
settingsUpdated = true;
enableControls(true);
}
}
void ConfigPipXtremeWidget::disconnected()
{
settingsUpdated = false;
enableControls(false);
if (settingsUpdated)
{
settingsUpdated = false;
enableControls(false);
}
}
void ConfigPipXtremeWidget::pairIDToggled(bool checked, quint8 idx)

View File

@ -53,9 +53,6 @@ private:
bool settingsUpdated;
// A timer that timesout the connction to the PipX.
QTimer *timeOut;
private slots:
void refreshValues();
void applySettings();

View File

@ -103,22 +103,22 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
addUAVObject("MixerSettings");
addUAVObject("ActuatorSettings");
ffTuningInProgress = false;
ffTuningPhase = false;
//Generate list of channels
QStringList channels;
channels << "None";
for (unsigned int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
//Generate lists of mixerTypeNames, mixerVectorNames, channelNames
channelNames << "None";
for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
mixerTypes << QString("Mixer%1Type").arg(i+1);
mixerVectors << QString("Mixer%1Vector").arg(i+1);
channels << QString("Channel%1").arg(i+1);
channelNames << QString("Channel%1").arg(i+1);
}
QStringList airframeTypes;
airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Ground" << "Custom";
m_aircraft->aircraftType->addItems(airframeTypes);
m_aircraft->aircraftType->setCurrentIndex(0); //Set default vehicle to Fixed Wing
QStringList fixedWingTypes;
@ -138,27 +138,13 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
m_aircraft->multirotorFrameType->addItems(multiRotorTypes);
m_aircraft->multirotorFrameType->setCurrentIndex(1); //Set default model to "Quad +"
// Now load all the channel assignements
//OLD STYLE: DO IT MANUALLY
// m_aircraft->triYawChannelBox->addItems(channels);
// m_aircraft->gvMotor1ChannelBox->addItems(channels);
// m_aircraft->gvMotor2ChannelBox->addItems(channels);
// m_aircraft->gvSteering1ChannelBox->addItems(channels);
// m_aircraft->gvSteering2ChannelBox->addItems(channels);
// m_aircraft->fwElevator1ChannelBox->addItems(channels);
// m_aircraft->fwElevator2ChannelBox->addItems(channels);
// m_aircraft->fwEngineChannelBox->addItems(channels);
// m_aircraft->fwRudder1ChannelBox->addItems(channels);
// m_aircraft->fwRudder2ChannelBox->addItems(channels);
// m_aircraft->fwAileron1ChannelBox->addItems(channels);
// m_aircraft->fwAileron2ChannelBox->addItems(channels);
//NEW STYLE: Loop through the widgets looking for all widgets that have "ChannelBox" in their name
// The upshot of this is that ALL new ComboBox widgets for selecting the output channel must have "ChannelBox" in their name
foreach(QComboBox *combobox, this->findChildren<QComboBox*>(QRegExp("\\S+ChannelBo\\S+")))//FOR WHATEVER REASON, THIS DOES NOT WORK WITH ChannelBox. ChannelBo is sufficiently accurate
{
combobox->addItems(channels);
}
combobox->addItems(channelNames);
}
// Setup the Multirotor picture in the Quad settings interface
m_aircraft->quadShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
@ -188,6 +174,27 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd);
}
// create and setup a MultiRotor config widget
m_multirotor = new ConfigMultiRotorWidget(m_aircraft);
m_multirotor->quad = quad;
m_multirotor->uiowner = this;
m_multirotor->setupUI(m_aircraft->multirotorFrameType->currentText());
// create and setup a GroundVehicle config widget
m_groundvehicle = new ConfigGroundVehicleWidget(m_aircraft);
m_groundvehicle->setupUI(m_aircraft->groundVehicleType->currentText() );
// create and setup a FixedWing config widget
m_fixedwing = new ConfigFixedWingWidget(m_aircraft);
m_fixedwing->setupUI(m_aircraft->fixedWingType->currentText() );
// create and setup a Helicopter config widget
m_heli = m_aircraft->widget_3;
m_heli->setupUI(QString("HeliCP"));
// initialize the ui to show the mixersettings tab
//mdl m_aircraft->tabWidget->setCurrentIndex(0);
//Connect aircraft type selection dropbox to callback function
connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int)));
@ -195,6 +202,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
connect(m_aircraft->multirotorFrameType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
connect(m_aircraft->groundVehicleType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
//mdl connect(m_heli->m_ccpm->ccpmType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
//Connect throttle curve reset pushbuttons to reset functions
connect(m_aircraft->fwThrottleReset, SIGNAL(clicked()), this, SLOT(resetFwMixer()));
@ -220,19 +228,12 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
connect(m_aircraft->ffTestBox2, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
//WHAT DOES THIS DO?
enableControls(false);
refreshWidgetsValues();
// Connect the help pushbutton
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
enableControls(false);
refreshWidgetsValues();
addToDirtyMonitor();
//Initialize GUI tabs //MOVING THIS FROM THE END OF THIS FUNCTION CAN CAUSE RUNTIME ERRORS DUE TO setupMultiRotorUI. WHY?
setupMultiRotorUI( m_aircraft->multirotorFrameType->currentText() );
setupGroundVehicleUI( m_aircraft->groundVehicleType->currentText() );
setupFixedWingUI( m_aircraft->fixedWingType->currentText() );
disableMouseWheelEvents();
}
@ -245,12 +246,95 @@ ConfigVehicleTypeWidget::~ConfigVehicleTypeWidget()
// Do nothing
}
/**
Static function to get currently assigned channelDescriptions
for all known vehicle types; instantiates the appropriate object
then asks it to supply channel descs
*/
QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
{
int i;
QStringList channelDesc;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager * objMngr = pm->getObject<UAVObjectManager>();
Q_ASSERT(objMngr);
// get an instance of systemsettings
SystemSettings * systemSettings = SystemSettings::GetInstance(objMngr);
Q_ASSERT(systemSettings);
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
switch (systemSettingsData.AirframeType)
{
// fixed wing
case SystemSettings::AIRFRAMETYPE_FIXEDWING:
case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON:
case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL:
{
ConfigFixedWingWidget* fixedwing = new ConfigFixedWingWidget();
channelDesc = fixedwing->getChannelDescriptions();
}
break;
// helicp
case SystemSettings::AIRFRAMETYPE_HELICP:
{
ConfigCcpmWidget* heli = new ConfigCcpmWidget();
channelDesc = heli->getChannelDescriptions();
}
break;
//multirotor
case SystemSettings::AIRFRAMETYPE_VTOL:
case SystemSettings::AIRFRAMETYPE_TRI:
case SystemSettings::AIRFRAMETYPE_QUADX:
case SystemSettings::AIRFRAMETYPE_QUADP:
case SystemSettings::AIRFRAMETYPE_OCTOV:
case SystemSettings::AIRFRAMETYPE_OCTOCOAXX:
case SystemSettings::AIRFRAMETYPE_OCTOCOAXP:
case SystemSettings::AIRFRAMETYPE_OCTO:
case SystemSettings::AIRFRAMETYPE_HEXAX:
case SystemSettings::AIRFRAMETYPE_HEXACOAX:
case SystemSettings::AIRFRAMETYPE_HEXA:
{
ConfigMultiRotorWidget* multi = new ConfigMultiRotorWidget();
channelDesc = multi->getChannelDescriptions();
}
break;
// ground
case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLECAR:
case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL:
case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE:
{
ConfigGroundVehicleWidget* ground = new ConfigGroundVehicleWidget();
channelDesc = ground->getChannelDescriptions();
}
break;
default:
{
for (i=0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++)
channelDesc.append(QString("-"));
}
break;
}
// for (i=0; i < channelDesc.count(); i++)
// qDebug() << QString("Channel %0 = %1").arg(i).arg(channelDesc[i]);
return channelDesc;
}
/**
Slot for switching the airframe type. We do it explicitely
rather than a signal in the UI, because we want to force a fitInView of the quad shapes.
This is because this method (fitinview) only works when the widget is shown.
*/
void ConfigVehicleTypeWidget::switchAirframeType(int index){
void ConfigVehicleTypeWidget::switchAirframeType(int index)
{
m_aircraft->airframesWidget->setCurrentIndex(index);
m_aircraft->quadShape->setSceneRect(quad->boundingRect());
m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio);
@ -331,7 +415,6 @@ void ConfigVehicleTypeWidget::toggleRudder2(int index)
}
}
/////////////////////////////////////////////////////////
/// Feed Forward Testing
/////////////////////////////////////////////////////////
@ -525,8 +608,10 @@ void ConfigVehicleTypeWidget::updateCustomThrottle2CurveValue(QList<double> list
/**
Refreshes the current value of the SystemSettings which holds the aircraft type
*/
void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *)
void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject * o)
{
Q_UNUSED(o);
if(!allObjectsUpdated())
return;
@ -609,7 +694,7 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *)
if (frameType.startsWith("FixedWing")) {
// Retrieve fixed wing settings
refreshFixedWingWidgetsValues(frameType);
m_fixedwing->refreshWidgetsValues(frameType);
} else if (frameType == "Tri" ||
frameType == "QuadX" || frameType == "QuadP" ||
@ -617,17 +702,18 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *)
frameType == "Octo" || frameType == "OctoV" || frameType == "OctoCoaxP" || frameType == "OctoCoaxX" ) {
// Retrieve multirotor settings
refreshMultiRotorWidgetsValues(frameType);
m_multirotor->refreshWidgetsValues(frameType);
} else if (frameType == "HeliCP") {
m_aircraft->widget_3->requestccpmUpdate();
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Helicopter"));//"Helicopter"
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Helicopter"));
m_heli->refreshWidgetsValues(frameType);
} else if (frameType.startsWith("GroundVehicle")) {
// Retrieve ground vehicle settings
refreshGroundVehicleWidgetsValues(frameType);
// Retrieve ground vehicle settings
m_groundvehicle->refreshWidgetsValues(frameType);
} else if (frameType == "Custom") {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Custom"));
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText("Custom"));
}
@ -641,13 +727,13 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *)
*/
void ConfigVehicleTypeWidget::setupAirframeUI(QString frameType)
{
bool dirty=isDirty();
if(frameType == "FixedWing" || frameType == "Elevator aileron rudder" ||
frameType == "FixedWingElevon" || frameType == "Elevon" ||
frameType == "FixedWingVtail" || frameType == "Vtail"){
setupFixedWingUI(frameType);
} else if (frameType == "Tri" || frameType == "Tricopter Y" ||
frameType == "FixedWingVtail" || frameType == "Vtail"){
m_fixedwing->setupUI(frameType);
}
else if (frameType == "Tri" || frameType == "Tricopter Y" ||
frameType == "QuadX" || frameType == "Quad X" ||
frameType == "QuadP" || frameType == "Quad +" ||
frameType == "Hexa" || frameType == "Hexacopter" ||
@ -658,13 +744,16 @@ void ConfigVehicleTypeWidget::setupAirframeUI(QString frameType)
frameType == "OctoCoaxP" || frameType == "Octo Coax +" ||
frameType == "OctoCoaxX" || frameType == "Octo Coax X" ) {
//Call multi-rotor setup UI
setupMultiRotorUI(frameType);
//Call multi-rotor setup UI
m_multirotor->setupUI(frameType);
}
else if (frameType == "HeliCP") {
m_heli->setupUI(frameType);
}
else if (frameType == "GroundVehicleCar" || frameType == "Turnable (car)" ||
frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)" ||
frameType == "GroundVehicleMotorcyle" || frameType == "Motorcycle") {
setupGroundVehicleUI(frameType);
frameType == "GroundVehicleMotorcyle" || frameType == "Motorcycle") {
m_groundvehicle->setupUI(frameType);
}
//SHOULDN'T THIS BE DONE ONLY IN QUAD SETUP, AND NOT ALL THE REST???
@ -685,26 +774,6 @@ void ConfigVehicleTypeWidget::resetField(UAVObjectField * field)
}
}
/**
Reset actuator values
*/
void ConfigVehicleTypeWidget::resetActuators()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
QList<UAVObjectField*> fieldList = obj->getFields();
// Reset all assignements first:
foreach (UAVObjectField* field, fieldList) {
// NOTE: we assume that all options in ActuatorSettings are a channel assignement
// except for the options called "ChannelBoxXXX"
if (field->getUnits().contains("channel")) {
field->setValue(field->getOptions().last());
}
}
}
/**
Updates the custom airframe settings based on the current airframe.
@ -712,58 +781,77 @@ void ConfigVehicleTypeWidget::resetActuators()
*/
void ConfigVehicleTypeWidget::updateCustomAirframeUI()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
QList<double> curveValues;
// If the 1st element of the curve is <= -10, then the curve
// is a straight line (that's how the mixer works on the mainboard):
if (field->getValue(0).toInt() <= -10) {
m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1);
} else {
double temp=0;
double value;
for (unsigned int i=0; i < field->getNumElements(); i++) {
value=field->getValue(i).toDouble();
temp+=value;
curveValues.append(value);
}
if(temp==0)
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
if (field)
{
// If the 1st element of the curve is <= -10, then the curve
// is a straight line (that's how the mixer works on the mainboard):
if (field->getValue(0).toInt() <= -10) {
m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1);
else
m_aircraft->customThrottle1Curve->initCurve(curveValues);
}
field = obj->getField(QString("ThrottleCurve2"));
curveValues.clear();
// If the 1st element of the curve is <= -10, then the curve
// is a straight line (that's how the mixer works on the mainboard):
if (field->getValue(0).toInt() <= -10) {
m_aircraft->customThrottle2Curve->initLinearCurve(field->getNumElements(),(double)1);
} else {
for (unsigned int i=0; i < field->getNumElements(); i++) {
curveValues.append(field->getValue(i).toDouble());
} else {
double temp=0;
double value;
for (unsigned int i=0; i < field->getNumElements(); i++) {
value=field->getValue(i).toDouble();
temp+=value;
curveValues.append(value);
}
if(temp==0)
m_aircraft->customThrottle1Curve->initLinearCurve(field->getNumElements(),(double)1);
else
m_aircraft->customThrottle1Curve->initCurve(curveValues);
}
}
curveValues.clear();
field = obj->getField(QString("ThrottleCurve2"));
if (field)
{
// If the 1st element of the curve is <= -10, then the curve
// is a straight line (that's how the mixer works on the mainboard):
if (field->getValue(0).toInt() <= -10) {
m_aircraft->customThrottle2Curve->initLinearCurve(field->getNumElements(),(double)1);
} else {
for (unsigned int i=0; i < field->getNumElements(); i++) {
curveValues.append(field->getValue(i).toDouble());
}
m_aircraft->customThrottle2Curve->initCurve(curveValues);
}
m_aircraft->customThrottle2Curve->initCurve(curveValues);
}
// Update the table:
for (int i=0; i<8; i++) {
field = obj->getField(mixerTypes.at(i));
QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,i);
QString s = field->getValue().toString();
q->setCurrentIndex(q->findText(s));
//bool en = (s != "Disabled");
field = obj->getField(mixerVectors.at(i));
int ti = field->getElementNames().indexOf("ThrottleCurve1");
m_aircraft->customMixerTable->item(1,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("ThrottleCurve2");
m_aircraft->customMixerTable->item(2,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("Roll");
m_aircraft->customMixerTable->item(3,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("Pitch");
m_aircraft->customMixerTable->item(4,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("Yaw");
m_aircraft->customMixerTable->item(5,i)->setText(field->getValue(ti).toString());
if (field)
{
QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,i);
if (q)
{
QString s = field->getValue().toString();
setComboCurrentIndex(q, q->findText(s));
}
field = obj->getField(mixerVectors.at(i));
if (field)
{
int ti = field->getElementNames().indexOf("ThrottleCurve1");
m_aircraft->customMixerTable->item(1,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("ThrottleCurve2");
m_aircraft->customMixerTable->item(2,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("Roll");
m_aircraft->customMixerTable->item(3,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("Pitch");
m_aircraft->customMixerTable->item(4,i)->setText(field->getValue(ti).toString());
ti = field->getElementNames().indexOf("Yaw");
m_aircraft->customMixerTable->item(5,i)->setText(field->getValue(ti).toString());
}
}
}
}
@ -777,23 +865,25 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI()
*/
void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
{
qDebug()<<"updateObjectsFromWidgets";
UAVDataObject* obj;
UAVObjectField* field;
QString airframeType = "Custom"; //Sets airframe type default to "Custom"
if (m_aircraft->aircraftType->currentText() == "Fixed Wing") {
airframeType = updateFixedWingObjectsFromWidgets();
} else if (m_aircraft->aircraftType->currentText() == "Multirotor") {
//update the mixer
airframeType = updateMultiRotorObjectsFromWidgets();
} else if (m_aircraft->aircraftType->currentText() == "Helicopter") {
airframeType = "HeliCP";
m_aircraft->widget_3->sendccpmUpdate();
} else if (m_aircraft->aircraftType->currentText() == "Ground") {
airframeType = updateGroundVehicleObjectsFromWidgets();
} else {
airframeType = "Custom";
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("FeedForward"));
airframeType = m_fixedwing->updateConfigObjectsFromWidgets();
}
else if (m_aircraft->aircraftType->currentText() == "Multirotor") {
airframeType = m_multirotor->updateConfigObjectsFromWidgets();
}
else if (m_aircraft->aircraftType->currentText() == "Helicopter") {
airframeType = m_heli->updateConfigObjectsFromWidgets();
}
else if (m_aircraft->aircraftType->currentText() == "Ground") {
airframeType = m_groundvehicle->updateConfigObjectsFromWidgets();
}
else {
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
field = obj->getField(QString("FeedForward"));
// Curve is also common to all quads:
field = obj->getField("ThrottleCurve1");
@ -826,14 +916,13 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
ti = field->getElementNames().indexOf("Yaw");
field->setValue(m_aircraft->customMixerTable->item(5,i)->text(),ti);
}
}
//WHAT DOES THIS DO?
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
UAVObjectField* field = obj->getField(QString("AirframeType"));
// set the airframe type
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
field = obj->getField(QString("AirframeType"));
field->setValue(airframeType);
updateCustomAirframeUI();
}
/**
@ -845,6 +934,16 @@ void ConfigVehicleTypeWidget::openHelp()
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Airframe+configuration", QUrl::StrictMode) );
}
/**
Helper function:
Sets the current index on supplied combobox to index
if it is within bounds 0 <= index < combobox.count()
*/
void ConfigVehicleTypeWidget::setComboCurrentIndex(QComboBox* box, int index)
{
if (index >= 0 && index < box->count())
box->setCurrentIndex(index);
}
/**
WHAT DOES THIS DO???
@ -873,6 +972,9 @@ void ConfigVehicleTypeWidget::addToDirtyMonitor()
addWidget(m_aircraft->multiMotorChannelBox6);
addWidget(m_aircraft->multiMotorChannelBox7);
addWidget(m_aircraft->multiMotorChannelBox8);
addWidget(m_aircraft->mrPitchMixLevel);
addWidget(m_aircraft->mrRollMixLevel);
addWidget(m_aircraft->mrYawMixLevel);
addWidget(m_aircraft->triYawChannelBox);
addWidget(m_aircraft->aircraftType);
addWidget(m_aircraft->fwEngineChannelBox);
@ -884,44 +986,44 @@ void ConfigVehicleTypeWidget::addToDirtyMonitor()
addWidget(m_aircraft->fwRudder2ChannelBox);
addWidget(m_aircraft->elevonSlider1);
addWidget(m_aircraft->elevonSlider2);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmType);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmTailChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmEngineChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoWChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoXChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoYChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmSingleServo);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoZChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleW);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleX);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmCorrectionAngle);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleZ);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleY);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivePassthrough);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkRoll);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkCyclic);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmRevoSlider);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmREVOspinBox);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveSlider);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivespinBox);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScale);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScaleBox);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmCyclicScale);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScale);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScaleBox);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScale);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScaleBox);
addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSlider);
addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSpinBox);
addWidget(m_aircraft->widget_3->m_ccpm->CurveType);
addWidget(m_aircraft->widget_3->m_ccpm->NumCurvePoints);
addWidget(m_aircraft->widget_3->m_ccpm->CurveValue1);
addWidget(m_aircraft->widget_3->m_ccpm->CurveValue2);
addWidget(m_aircraft->widget_3->m_ccpm->CurveValue3);
addWidget(m_aircraft->widget_3->m_ccpm->CurveToGenerate);
addWidget(m_aircraft->widget_3->m_ccpm->CurveSettings);
addWidget(m_aircraft->widget_3->m_ccpm->ThrottleCurve);
addWidget(m_aircraft->widget_3->m_ccpm->PitchCurve);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmAdvancedSettingsTable);
addWidget(m_heli->m_ccpm->ccpmType);
addWidget(m_heli->m_ccpm->ccpmTailChannel);
addWidget(m_heli->m_ccpm->ccpmEngineChannel);
addWidget(m_heli->m_ccpm->ccpmServoWChannel);
addWidget(m_heli->m_ccpm->ccpmServoXChannel);
addWidget(m_heli->m_ccpm->ccpmServoYChannel);
addWidget(m_heli->m_ccpm->ccpmSingleServo);
addWidget(m_heli->m_ccpm->ccpmServoZChannel);
addWidget(m_heli->m_ccpm->ccpmAngleW);
addWidget(m_heli->m_ccpm->ccpmAngleX);
addWidget(m_heli->m_ccpm->ccpmCorrectionAngle);
addWidget(m_heli->m_ccpm->ccpmAngleZ);
addWidget(m_heli->m_ccpm->ccpmAngleY);
addWidget(m_heli->m_ccpm->ccpmCollectivePassthrough);
addWidget(m_heli->m_ccpm->ccpmLinkRoll);
addWidget(m_heli->m_ccpm->ccpmLinkCyclic);
addWidget(m_heli->m_ccpm->ccpmRevoSlider);
addWidget(m_heli->m_ccpm->ccpmREVOspinBox);
addWidget(m_heli->m_ccpm->ccpmCollectiveSlider);
addWidget(m_heli->m_ccpm->ccpmCollectivespinBox);
addWidget(m_heli->m_ccpm->ccpmCollectiveScale);
addWidget(m_heli->m_ccpm->ccpmCollectiveScaleBox);
addWidget(m_heli->m_ccpm->ccpmCyclicScale);
addWidget(m_heli->m_ccpm->ccpmPitchScale);
addWidget(m_heli->m_ccpm->ccpmPitchScaleBox);
addWidget(m_heli->m_ccpm->ccpmRollScale);
addWidget(m_heli->m_ccpm->ccpmRollScaleBox);
addWidget(m_heli->m_ccpm->SwashLvlPositionSlider);
addWidget(m_heli->m_ccpm->SwashLvlPositionSpinBox);
addWidget(m_heli->m_ccpm->CurveType);
addWidget(m_heli->m_ccpm->NumCurvePoints);
addWidget(m_heli->m_ccpm->CurveValue1);
addWidget(m_heli->m_ccpm->CurveValue2);
addWidget(m_heli->m_ccpm->CurveValue3);
addWidget(m_heli->m_ccpm->CurveToGenerate);
addWidget(m_heli->m_ccpm->CurveSettings);
addWidget(m_heli->m_ccpm->ThrottleCurve);
addWidget(m_heli->m_ccpm->PitchCurve);
addWidget(m_heli->m_ccpm->ccpmAdvancedSettingsTable);
}

View File

@ -33,6 +33,12 @@
#include "uavobjectmanager.h"
#include "uavobject.h"
#include "uavtalk/telemetrymanager.h"
#include "cfg_vehicletypes/configccpmwidget.h"
#include "cfg_vehicletypes/configfixedwingwidget.h"
#include "cfg_vehicletypes/configmultirotorwidget.h"
#include "cfg_vehicletypes/configgroundvehiclewidget.h"
#include <QtGui/QWidget>
#include <QList>
#include <QItemDelegate>
@ -47,54 +53,40 @@ public:
ConfigVehicleTypeWidget(QWidget *parent = 0);
~ConfigVehicleTypeWidget();
static QStringList getChannelDescriptions();
private:
Ui_AircraftWidget *m_aircraft;
bool setupFrameFixedWing(QString airframeType);
bool setupFrameElevon(QString airframeType);
bool setupFrameVtail(QString airframeType);
bool setupQuad(bool pLayout);
bool setupHexa(bool pLayout);
bool setupOcto();
bool setupGroundVehicleCar(QString airframeType);
bool setupGroundVehicleDifferential(QString airframeType);
bool setupGroundVehicleMotorcycle(QString airframeType);
ConfigCcpmWidget *m_heli;
ConfigFixedWingWidget *m_fixedwing;
ConfigMultiRotorWidget *m_multirotor;
ConfigGroundVehicleWidget *m_groundvehicle;
void updateCustomAirframeUI();
bool setupMultiRotorMixer(double mixerFactors[8][3]);
void setupMotors(QList<QString> motorList);
void addToDirtyMonitor();
void resetField(UAVObjectField * field);
void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue);
void resetActuators();
//void setMixerChannel(int channelNumber, bool channelIsMotor, QList<double> vector);
void setupQuadMotor(int channel, double roll, double pitch, double yaw);
//void setMixerChannel(int channelNumber, bool channelIsMotor, QList<double> vector);
QStringList channelNames;
QStringList mixerTypes;
QStringList mixerVectors;
QGraphicsSvgItem *quad;
bool ffTuningInProgress;
bool ffTuningPhase;
UAVObject::Metadata accInitialData;
private slots:
virtual void refreshWidgetsValues(UAVObject * obj = NULL);
void refreshFixedWingWidgetsValues(QString frameType);
void refreshMultiRotorWidgetsValues(QString frameType);
void refreshGroundVehicleWidgetsValues(QString frameType);
void updateObjectsFromWidgets();
QString updateFixedWingObjectsFromWidgets();
QString updateMultiRotorObjectsFromWidgets();
QString updateGroundVehicleObjectsFromWidgets();
// void saveAircraftUpdate();
virtual void refreshWidgetsValues(UAVObject * o=NULL);
virtual void updateObjectsFromWidgets();
void setComboCurrentIndex(QComboBox* box, int index);
void setupAirframeUI(QString type);
void setupFixedWingUI(QString frameType);
void setupMultiRotorUI(QString frameType);
void setupGroundVehicleUI(QString frameType);
void throwMultiRotorChannelConfigError(int numMotors);
void throwFixedWingChannelConfigError(QString airframeType);
void throwGroundVehicleChannelConfigError(QString airframeType);
void toggleAileron2(int index);
void toggleElevator2(int index);

View File

@ -2,6 +2,7 @@
#include "ui_inputchannelform.h"
#include "manualcontrolsettings.h"
#include "gcsreceiver.h"
inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
ConfigTaskWidget(parent),
@ -115,7 +116,7 @@ void inputChannelForm::groupUpdated()
count = 18;
break;
case ManualControlSettings::CHANNELGROUPS_GCS:
count = 5;
count = GCSReceiver::CHANNEL_NUMELEM;
break;
case ManualControlSettings::CHANNELGROUPS_NONE:
count = 0;

View File

@ -145,7 +145,7 @@
<widget class="QLineEdit" name="PairID1"/>
</item>
<item row="0" column="3">
<widget class="QProgressBar" name="PairSignalStrength1">
<widget class="QProgressBar" name="PairSignalStrengthBar1">
<property name="minimum">
<number>-127</number>
</property>
@ -156,7 +156,7 @@
<number>-127</number>
</property>
<property name="textVisible">
<bool>true</bool>
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
@ -174,7 +174,7 @@
<widget class="QLineEdit" name="PairID2"/>
</item>
<item row="1" column="3">
<widget class="QProgressBar" name="PairSignalStrength2">
<widget class="QProgressBar" name="PairSignalStrengthBar2">
<property name="minimum">
<number>-127</number>
</property>
@ -185,7 +185,7 @@
<number>0</number>
</property>
<property name="textVisible">
<bool>true</bool>
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
@ -203,7 +203,7 @@
<widget class="QLineEdit" name="PairID3"/>
</item>
<item row="2" column="3">
<widget class="QProgressBar" name="PairSignalStrength3">
<widget class="QProgressBar" name="PairSignalStrengthBar3">
<property name="minimum">
<number>-127</number>
</property>
@ -214,7 +214,7 @@
<number>0</number>
</property>
<property name="textVisible">
<bool>true</bool>
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
@ -232,7 +232,7 @@
<widget class="QLineEdit" name="PairID4"/>
</item>
<item row="3" column="3">
<widget class="QProgressBar" name="PairSignalStrength4">
<widget class="QProgressBar" name="PairSignalStrengthBar4">
<property name="minimum">
<number>-127</number>
</property>
@ -243,13 +243,41 @@
<number>0</number>
</property>
<property name="textVisible">
<bool>true</bool>
<bool>false</bool>
</property>
<property name="format">
<string>%v dBm</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="PairSignalStrengthLabel1">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="PairSignalStrengthLabel2">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QLabel" name="PairSignalStrengthLabel3">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QLabel" name="PairSignalStrengthLabel4">
<property name="text">
<string>-100dB</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
@ -603,7 +631,7 @@
</widget>
</item>
<item row="9" column="0">
<widget class="QLabel" name="label_18">
<widget class="QLabel" name="RetriesLabel">
<property name="text">
<string>Retries</string>
</property>
@ -747,9 +775,9 @@
</widget>
</item>
<item row="13" column="0">
<widget class="QLabel" name="TXRateLabel">
<widget class="QLabel" name="DroppedLabel">
<property name="text">
<string>TX Rate (B/s)</string>
<string>Dropped</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
@ -757,7 +785,7 @@
</widget>
</item>
<item row="13" column="1">
<widget class="QLineEdit" name="TXRate">
<widget class="QLineEdit" name="Dropped">
<property name="font">
<font>
<weight>75</weight>
@ -783,6 +811,42 @@
</widget>
</item>
<item row="14" column="0">
<widget class="QLabel" name="TXRateLabel">
<property name="text">
<string>TX Rate (B/s)</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="14" column="1">
<widget class="QLineEdit" name="TXRate">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">QLineEdit {
border: none;
border-radius: 1px;
padding: 0 8px;
background: rgba(0, 0, 0, 16);
/* background: transparent; */
/* selection-background-color: darkgray;*/
}</string>
</property>
<property name="frame">
<bool>false</bool>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="15" column="0">
<widget class="QLabel" name="RXRateLabel">
<property name="text">
<string>RX Rate (B/s)</string>
@ -792,7 +856,7 @@
</property>
</widget>
</item>
<item row="14" column="1">
<item row="15" column="1">
<widget class="QLineEdit" name="RXRate">
<property name="font">
<font>

View File

@ -124,6 +124,17 @@ void ModeManager::activateMode(const QString &id)
m_modeStack->setCurrentIndex(index);
}
void ModeManager::activateModeByWorkspaceName(const QString &id)
{
for (int i = 0; i < m_modes.count(); ++i) {
if (m_modes.at(i)->name() == id)
{
m_modeStack->setCurrentIndex(i);
return;
}
}
}
void ModeManager::objectAdded(QObject *obj)
{
IMode *mode = Aggregation::query<IMode>(obj);

View File

@ -80,6 +80,7 @@ signals:
public slots:
void activateMode(const QString &id);
void activateModeByWorkspaceName(const QString &id);
void setFocusToCurrentMode();
private slots:

View File

@ -0,0 +1,468 @@
#include "aerosimrc.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/icore.h>
#include <coreplugin/threadmanager.h>
AeroSimRCSimulator::AeroSimRCSimulator(const SimulatorSettings &params)
: Simulator(params)
{
udpCounterASrecv = 0;
}
AeroSimRCSimulator::~AeroSimRCSimulator()
{
}
bool AeroSimRCSimulator::setupProcess()
{
QMutexLocker locker(&lock);
return true;
}
void AeroSimRCSimulator::setupUdpPorts(const QString &host, int inPort, int outPort)
{
Q_UNUSED(outPort)
if (inSocket->bind(QHostAddress(host), inPort))
emit processOutput("Successfully bound to address " + host + ", port " + QString::number(inPort) + "\n");
else
emit processOutput("Cannot bind to address " + host + ", port " + QString::number(inPort) + "\n");
}
void AeroSimRCSimulator::transmitUpdate()
{
// read actuator output
ActuatorCommand::DataFields actCmdData;
actCmdData = actCommand->getData();
float channels[10];
for (int i = 0; i < 10; ++i) {
qint16 ch = actCmdData.Channel[i];
float out = -1.0;
if (ch >= 1000 && ch <= 2000) {
ch -= 1000;
out = ((float)ch / 500.0) - 1.0;
}
channels[i] = out;
}
// read flight status
FlightStatus::DataFields flightData;
flightData = flightStatus->getData();
quint8 armed;
quint8 mode;
armed = flightData.Armed;
mode = flightData.FlightMode;
QByteArray data;
// 50 - current size of values, 4(quint32) + 10*4(float) + 2(quint8) + 4(quint32)
data.resize(50);
QDataStream stream(&data, QIODevice::WriteOnly);
stream.setFloatingPointPrecision(QDataStream::SinglePrecision);
stream << quint32(0x52434D44); // magic header, "RCMD"
for (int i = 0; i < 10; ++i)
stream << channels[i]; // channels
stream << armed << mode; // flight status
stream << udpCounterASrecv; // packet counter
if (outSocket->writeDatagram(data, QHostAddress(settings.remoteAddress), settings.outPort) == -1) {
qDebug() << "write failed: " << outSocket->errorString();
}
#ifdef DBG_TIMERS
static int cntTX = 0;
if (cntTX >= 100) {
qDebug() << "TX=" << 1000.0 * 100 / timeTX.restart();
cntTX = 0;
} else {
++cntTX;
}
#endif
}
void AeroSimRCSimulator::processUpdate(const QByteArray &data)
{
// check size
if (data.size() > 188) {
qDebug() << "!!! big datagram: " << data.size();
return;
}
QByteArray buf = data;
QDataStream stream(&buf, QIODevice::ReadOnly);
stream.setFloatingPointPrecision(QDataStream::SinglePrecision);
// check magic header
quint32 magic;
stream >> magic;
if (magic != 0x4153494D) { // "AERO"
qDebug() << "wrong magic: " << magic << ", correct: " << quint32(0x4153494D);
return;
}
float timeStep,
homeX, homeY, homeZ,
WpHX, WpHY, WpLat, WpLon,
posX, posY, posZ, // world
velX, velY, velZ, // world
angX, angY, angZ, // model
accX, accY, accZ, // model
lat, lon, agl, // world
yaw, pitch, roll, // model
volt, curr,
rx, ry, rz, fx, fy, fz, ux, uy, uz, // matrix
ch[8];
stream >> timeStep;
stream >> homeX >> homeY >> homeZ;
stream >> WpHX >> WpHY >> WpLat >> WpLon;
stream >> posX >> posY >> posZ;
stream >> velX >> velY >> velZ;
stream >> angX >> angY >> angZ;
stream >> accX >> accY >> accZ;
stream >> lat >> lon >> agl;
stream >> yaw >> pitch >> roll;
stream >> volt >> curr;
stream >> rx >> ry >> rz >> fx >> fy >> fz >> ux >> uy >> uz;
stream >> ch[0] >> ch[1] >> ch[2] >> ch[3] >> ch[4] >> ch[5] >> ch[6] >> ch[7];
stream >> udpCounterASrecv;
/**********************************************************************************************/
QTime currentTime = QTime::currentTime();
/**********************************************************************************************/
static bool firstRun = true;
if (settings.homeLocation) {
if (firstRun) {
HomeLocation::DataFields homeData;
homeData = posHome->getData();
homeData.Latitude = WpLat * 10e6;
homeData.Longitude = WpLon * 10e6;
homeData.Altitude = homeZ;
homeData.Set = HomeLocation::SET_TRUE;
posHome->setData(homeData);
firstRun = false;
}
if (settings.homeLocRate > 0) {
static QTime homeLocTime = currentTime;
if (homeLocTime.secsTo(currentTime) >= settings.homeLocRate) {
firstRun = true;
homeLocTime = currentTime;
}
}
}
/**********************************************************************************************/
if (settings.attRaw || settings.attActual) {
QMatrix4x4 mat;
mat = QMatrix4x4( fy, fx, -fz, 0.0, // model matrix
ry, rx, -rz, 0.0, // (X,Y,Z) -> (+Y,+X,-Z)
-uy, -ux, uz, 0.0,
0.0, 0.0, 0.0, 1.0);
mat.optimize();
QQuaternion quat; // model quat
asMatrix2Quat(mat, quat);
// rotate gravity
QVector3D acc = QVector3D(accY, accX, -accZ); // accel (X,Y,Z) -> (+Y,+X,-Z)
QVector3D gee = QVector3D(0.0, 0.0, -GEE);
QQuaternion qWorld = quat.conjugate();
gee = qWorld.rotatedVector(gee);
acc += gee;
/*************************************************************************************/
if (settings.attRaw) {
Accels::DataFields accelsData;
accelsData = accels->getData();
Gyros::DataFields gyrosData;
gyrosData = gyros->getData();
gyrosData.x = angY * RAD2DEG; // gyros (X,Y,Z) -> (+Y,+X,-Z)
gyrosData.y = angX * RAD2DEG;
gyrosData.z = angZ * -RAD2DEG;
accelsData.x = acc.x();
accelsData.y = acc.y();
accelsData.z = acc.z();
accels->setData(accelsData);
gyros->setData(gyrosData);
}
/*************************************************************************************/
if (settings.attActHW) {
// do nothing
/*****************************************/
} else if (settings.attActSim) {
// take all data from simulator
AttitudeActual::DataFields attActData;
attActData = attActual->getData();
QVector3D rpy; // model roll, pitch, yaw
asMatrix2RPY(mat, rpy);
attActData.Roll = rpy.x();
attActData.Pitch = rpy.y();
attActData.Yaw = rpy.z();
attActData.q1 = quat.scalar();
attActData.q2 = quat.x();
attActData.q3 = quat.y();
attActData.q4 = quat.z();
attActual->setData(attActData);
/*****************************************/
} else if (settings.attActCalc) {
// calculate RPY with code from Attitude module
AttitudeActual::DataFields attActData;
attActData = attActual->getData();
static float q[4] = {1, 0, 0, 0};
static float gyro_correct_int2 = 0;
float dT = timeStep;
AttitudeSettings::DataFields attSettData = attSettings->getData();
float accelKp = attSettData.AccelKp * 0.1666666666666667;
float accelKi = attSettData.AccelKp * 0.1666666666666667;
float yawBiasRate = attSettData.YawBiasRate;
// calibrate sensors on arming
if (flightStatus->getData().Armed == FlightStatus::ARMED_ARMING) {
accelKp = 2.0;
accelKi = 0.9;
}
float gyro[3] = {angY * RAD2DEG, angX * RAD2DEG, angZ * -RAD2DEG};
float attRawAcc[3] = {acc.x(), acc.y(), acc.z()};
// code from Attitude module begin ///////////////////////////////
float *accels = attRawAcc;
float grot[3];
float accel_err[3];
// Rotate gravity to body frame and cross with accels
grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2]));
grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1]));
grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]);
// CrossProduct
{
accel_err[0] = accels[1]*grot[2] - grot[1]*accels[2];
accel_err[1] = grot[0]*accels[2] - accels[0]*grot[2];
accel_err[2] = accels[0]*grot[1] - grot[0]*accels[1];
}
// Account for accel magnitude
float accel_mag = sqrt(accels[0] * accels[0] + accels[1] * accels[1] + accels[2] * accels[2]);
accel_err[0] /= accel_mag;
accel_err[1] /= accel_mag;
accel_err[2] /= accel_mag;
// Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s
gyro_correct_int2 += -gyro[2] * yawBiasRate;
// Correct rates based on error, integral component dealt with in updateSensors
gyro[0] += accel_err[0] * accelKp / dT;
gyro[1] += accel_err[1] * accelKp / dT;
gyro[2] += accel_err[2] * accelKp / dT + gyro_correct_int2;
// Work out time derivative from INSAlgo writeup
// Also accounts for the fact that gyros are in deg/s
float qdot[4];
qdot[0] = (-q[1] * gyro[0] - q[2] * gyro[1] - q[3] * gyro[2]) * dT * M_PI / 180 / 2;
qdot[1] = (+q[0] * gyro[0] - q[3] * gyro[1] + q[2] * gyro[2]) * dT * M_PI / 180 / 2;
qdot[2] = (+q[3] * gyro[0] + q[0] * gyro[1] - q[1] * gyro[2]) * dT * M_PI / 180 / 2;
qdot[3] = (-q[2] * gyro[0] + q[1] * gyro[1] + q[0] * gyro[2]) * dT * M_PI / 180 / 2;
// Take a time step
q[0] += qdot[0];
q[1] += qdot[1];
q[2] += qdot[2];
q[3] += qdot[3];
if(q[0] < 0) {
q[0] = -q[0];
q[1] = -q[1];
q[2] = -q[2];
q[3] = -q[3];
}
// Renomalize
float qmag = sqrt((q[0] * q[0]) + (q[1] * q[1]) + (q[2] * q[2]) + (q[3] * q[3]));
q[0] /= qmag;
q[1] /= qmag;
q[2] /= qmag;
q[3] /= qmag;
// If quaternion has become inappropriately short or is nan reinit.
// THIS SHOULD NEVER ACTUALLY HAPPEN
if((fabs(qmag) < 1e-3) || (qmag != qmag)) {
q[0] = 1;
q[1] = 0;
q[2] = 0;
q[3] = 0;
}
float rpy2[3];
// Quaternion2RPY
{
float q0s, q1s, q2s, q3s;
q0s = q[0] * q[0];
q1s = q[1] * q[1];
q2s = q[2] * q[2];
q3s = q[3] * q[3];
float R13, R11, R12, R23, R33;
R13 = 2 * (q[1] * q[3] - q[0] * q[2]);
R11 = q0s + q1s - q2s - q3s;
R12 = 2 * (q[1] * q[2] + q[0] * q[3]);
R23 = 2 * (q[2] * q[3] + q[0] * q[1]);
R33 = q0s - q1s - q2s + q3s;
rpy2[1] = RAD2DEG * asinf(-R13); // pitch always between -pi/2 to pi/2
rpy2[2] = RAD2DEG * atan2f(R12, R11);
rpy2[0] = RAD2DEG * atan2f(R23, R33);
}
attActData.Roll = rpy2[0];
attActData.Pitch = rpy2[1];
attActData.Yaw = rpy2[2];
attActData.q1 = q[0];
attActData.q2 = q[1];
attActData.q3 = q[2];
attActData.q4 = q[3];
attActual->setData(attActData);
/*****************************************/
}
}
/**********************************************************************************************/
if (settings.gcsReciever) {
static QTime gcsRcvrTime = currentTime;
if (!settings.manualOutput || gcsRcvrTime.msecsTo(currentTime) >= settings.outputRate) {
GCSReceiver::DataFields gcsRcvrData;
gcsRcvrData = gcsReceiver->getData();
for (int i = 0; i < 8; ++i)
gcsRcvrData.Channel[i] = 1500 + (ch[i] * 500);
gcsReceiver->setData(gcsRcvrData);
if (settings.manualOutput)
gcsRcvrTime = currentTime;
}
} else if (settings.manualControl) {
// not implemented yet
}
/**********************************************************************************************/
if (settings.gpsPosition) {
static QTime gpsPosTime = currentTime;
if (gpsPosTime.msecsTo(currentTime) >= settings.gpsPosRate) {
GPSPosition::DataFields gpsPosData;
gpsPosData = gpsPosition->getData();
gpsPosData.Altitude = posZ;
gpsPosData.Heading = yaw * RAD2DEG;
gpsPosData.Latitude = lat * 10e6;
gpsPosData.Longitude = lon * 10e6;
gpsPosData.Groundspeed = qSqrt(velX * velX + velY * velY);
gpsPosData.GeoidSeparation = 0.0;
gpsPosData.Satellites = 8;
gpsPosData.PDOP = 3.0;
gpsPosData.Status = GPSPosition::STATUS_FIX3D;
gpsPosition->setData(gpsPosData);
gpsPosTime = currentTime;
}
}
/**********************************************************************************************/
if (settings.sonarAltitude) {
static QTime sonarAltTime = currentTime;
if (sonarAltTime.msecsTo(currentTime) >= settings.sonarAltRate) {
SonarAltitude::DataFields sonarAltData;
sonarAltData = sonarAlt->getData();
float sAlt = settings.sonarMaxAlt;
// 0.35 rad ~= 20 degree
if ((agl < (sAlt * 2.0)) && (roll < 0.35) && (pitch < 0.35)) {
float x = agl * qTan(roll);
float y = agl * qTan(pitch);
float h = qSqrt(x*x + y*y + agl*agl);
sAlt = qMin(h, sAlt);
}
sonarAltData.Altitude = sAlt;
sonarAlt->setData(sonarAltData);
sonarAltTime = currentTime;
}
}
/**********************************************************************************************/
/*
BaroAltitude::DataFields altActData;
altActData = altActual->getData();
altActData.Altitude = posZ;
altActual->setData(altActData);
PositionActual::DataFields posActData;
posActData = posActual->getData();
posActData.North = posY * 100;
posActData.East = posX * 100;
posActData.Down = posZ * -100;
posActual->setData(posActData);
VelocityActual::DataFields velActData;
velActData = velActual->getData();
velActData.North = velY * 100;
velActData.East = velX * 100;
velActData.Down = velZ * 100;
velActual->setData(velActData);
*/
#ifdef DBG_TIMERS
static int cntRX = 0;
if (cntRX >= 100) {
qDebug() << "RX=" << 1000.0 * 100 / timeRX.restart();
cntRX = 0;
} else {
++cntRX;
}
#endif
}
// transfomations
void AeroSimRCSimulator::asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q)
{
qreal w, x, y, z;
// w always >= 0
w = qSqrt(qMax(0.0, 1.0 + m(0, 0) + m(1, 1) + m(2, 2))) / 2.0;
x = qSqrt(qMax(0.0, 1.0 + m(0, 0) - m(1, 1) - m(2, 2))) / 2.0;
y = qSqrt(qMax(0.0, 1.0 - m(0, 0) + m(1, 1) - m(2, 2))) / 2.0;
z = qSqrt(qMax(0.0, 1.0 - m(0, 0) - m(1, 1) + m(2, 2))) / 2.0;
x = copysign(x, (m(1, 2) - m(2, 1)));
y = copysign(y, (m(2, 0) - m(0, 2)));
z = copysign(z, (m(0, 1) - m(1, 0)));
q.setScalar(w);
q.setX(x);
q.setY(y);
q.setZ(z);
}
void AeroSimRCSimulator::asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy)
{
qreal roll, pitch, yaw;
if (qFabs(m(0, 2)) > 0.998) {
// ~86.3°, gimbal lock
roll = 0.0;
pitch = copysign(M_PI_2, -m(0, 2));
yaw = qAtan2(-m(1, 0), m(1, 1));
} else {
roll = qAtan2(m(1, 2), m(2, 2));
pitch = qAsin(-m(0, 2));
yaw = qAtan2(m(0, 1), m(0, 0));
}
rpy.setX(roll * RAD2DEG);
rpy.setY(pitch * RAD2DEG);
rpy.setZ(yaw * RAD2DEG);
}

View File

@ -0,0 +1,46 @@
#ifndef AEROSIMRC_H
#define AEROSIMRC_H
#include <QObject>
#include <QVector3D>
#include <QQuaternion>
#include <QMatrix4x4>
#include "simulatorv2.h"
class AeroSimRCSimulator: public Simulator
{
Q_OBJECT
public:
AeroSimRCSimulator(const SimulatorSettings &params);
~AeroSimRCSimulator();
bool setupProcess();
void setupUdpPorts(const QString& host, int inPort, int outPort);
private slots:
void transmitUpdate();
private:
quint32 udpCounterASrecv; //keeps track of udp packets received by ASim
void processUpdate(const QByteArray &data);
void asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q);
void asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy);
};
class AeroSimRCSimulatorCreator : public SimulatorCreator
{
public:
AeroSimRCSimulatorCreator(const QString &classId, const QString &description)
: SimulatorCreator (classId, description)
{}
Simulator* createSimulator(const SimulatorSettings &params)
{
return new AeroSimRCSimulator(params);
}
};
#endif // AEROSIMRC_H

View File

@ -0,0 +1,12 @@
<plugin name="HITLv2" version="1.0.0" compatVersion="1.0.0">
<vendor>The OpenPilot Project</vendor>
<copyright>(C) 2011 OpenPilot Project</copyright>
<license>The GNU Public License (GPL) Version 3</license>
<description>Hardware In The Loop Simulation (v2)</description>
<url>http://www.openpilot.org</url>
<dependencyList>
<dependency name="Core" version="1.0.0"/>
<dependency name="UAVObjects" version="1.0.0"/>
<dependency name="UAVTalk" version="1.0.0"/>
</dependencyList>
</plugin>

View File

@ -0,0 +1,27 @@
TEMPLATE = lib
TARGET = HITLV2
QT += network
include(../../openpilotgcsplugin.pri)
include(hitlv2_dependencies.pri)
HEADERS += \
aerosimrc.h \
hitlv2configuration.h \
hitlv2factory.h \
hitlv2gadget.h \
hitlv2optionspage.h \
hitlv2plugin.h \
hitlv2widget.h \
simulatorv2.h
SOURCES += \
aerosimrc.cpp \
hitlv2configuration.cpp \
hitlv2factory.cpp \
hitlv2gadget.cpp \
hitlv2optionspage.cpp \
hitlv2plugin.cpp \
hitlv2widget.cpp \
simulatorv2.cpp
OTHER_FILES += hitlv2.pluginspec
FORMS += \
hitlv2optionspage.ui \
hitlv2widget.ui

View File

@ -0,0 +1,4 @@
include(../../plugins/uavobjects/uavobjects.pri)
include(../../plugins/uavtalk/uavtalk.pri)
#include(../../plugins/coreplugin/coreplugin.pri)
#include(../../libs/utils/utils.pri)

View File

@ -0,0 +1,178 @@
/**
******************************************************************************
*
* @file hitlconfiguration.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2configuration.h"
HITLConfiguration::HITLConfiguration(QString classId,
QSettings* qSettings,
QObject *parent)
: IUAVGadgetConfiguration(classId, parent)
{
// qDebug() << "HITLV2Configuration";
// default values
QString simulatorId = "ASimRC";
QString hostAddress = "127.0.0.1";
int inPort = 40100;
QString remoteAddress = "127.0.0.1";
int outPort = 40200;
QString binPath = "";
QString dataPath = "";
bool homeLocation = true;
quint16 homeLocRate = 0;
bool attRaw = true;
quint8 attRawRate = 20;
bool attActual = true;
bool attActHW = false;
bool attActSim = true;
bool attActCalc = false;
bool sonarAltitude = false;
float sonarMaxAlt = 5.0;
quint16 sonarAltRate = 50;
bool gpsPosition = true;
quint16 gpsPosRate = 200;
bool inputCommand = true;
bool gcsReciever = true;
bool manualControl = false;
bool manualOutput = false;
quint8 outputRate = 20;
// if a saved configuration exists load it
if (qSettings != 0) {
settings.simulatorId = qSettings->value("simulatorId", simulatorId).toString();
settings.hostAddress = qSettings->value("hostAddress", hostAddress).toString();
settings.inPort = qSettings->value("inPort", inPort).toInt();
settings.remoteAddress = qSettings->value("remoteAddress", remoteAddress).toString();
settings.outPort = qSettings->value("outPort", outPort).toInt();
settings.binPath = qSettings->value("binPath", binPath).toString();
settings.dataPath = qSettings->value("dataPath", dataPath).toString();
settings.homeLocation = qSettings->value("homeLocation", homeLocation).toBool();
settings.homeLocRate = qSettings->value("homeLocRate", homeLocRate).toInt();
settings.attRaw = qSettings->value("attRaw", attRaw).toBool();
settings.attRawRate = qSettings->value("attRawRate", attRawRate).toInt();
settings.attActual = qSettings->value("attActual", attActual).toBool();
settings.attActHW = qSettings->value("attActHW", attActHW).toBool();
settings.attActSim = qSettings->value("attActSim", attActSim).toBool();
settings.attActCalc = qSettings->value("attActCalc", attActCalc).toBool();
settings.sonarAltitude = qSettings->value("sonarAltitude", sonarAltitude).toBool();
settings.sonarMaxAlt = qSettings->value("sonarMaxAlt", sonarMaxAlt).toFloat();
settings.sonarAltRate = qSettings->value("sonarAltRate", sonarAltRate).toInt();
settings.gpsPosition = qSettings->value("gpsPosition", gpsPosition).toBool();
settings.gpsPosRate = qSettings->value("gpsPosRate", gpsPosRate).toInt();
settings.inputCommand = qSettings->value("inputCommand", inputCommand).toBool();
settings.gcsReciever = qSettings->value("gcsReciever", gcsReciever).toBool();
settings.manualControl = qSettings->value("manualControl", manualControl).toBool();
settings.manualOutput = qSettings->value("manualOutput", manualOutput).toBool();
settings.outputRate = qSettings->value("outputRate", outputRate).toInt();
} else {
settings.simulatorId = simulatorId;
settings.hostAddress = hostAddress;
settings.inPort = inPort;
settings.remoteAddress = remoteAddress;
settings.outPort = outPort;
settings.binPath = binPath;
settings.dataPath = dataPath;
settings.homeLocation = homeLocation;
settings.homeLocRate = homeLocRate;
settings.attRaw = attRaw;
settings.attRawRate = attRawRate;
settings.attActual = attActual;
settings.attActHW = attActHW;
settings.attActSim = attActSim;
settings.attActCalc = attActCalc;
settings.sonarAltitude = sonarAltitude;
settings.sonarMaxAlt = sonarMaxAlt;
settings.sonarAltRate = sonarAltRate;
settings.gpsPosition = gpsPosition;
settings.gpsPosRate = gpsPosRate;
settings.inputCommand = inputCommand;
settings.gcsReciever = gcsReciever;
settings.manualControl = manualControl;
settings.manualOutput = manualOutput;
settings.outputRate = outputRate;
}
}
IUAVGadgetConfiguration *HITLConfiguration::clone()
{
HITLConfiguration *m = new HITLConfiguration(this->classId());
m->settings = settings;
return m;
}
void HITLConfiguration::saveConfig(QSettings* qSettings) const
{
qSettings->setValue("simulatorId", settings.simulatorId);
qSettings->setValue("hostAddress", settings.hostAddress);
qSettings->setValue("inPort", settings.inPort);
qSettings->setValue("remoteAddress", settings.remoteAddress);
qSettings->setValue("outPort", settings.outPort);
qSettings->setValue("binPath", settings.binPath);
qSettings->setValue("dataPath", settings.dataPath);
qSettings->setValue("homeLocation", settings.homeLocation);
qSettings->setValue("homeLocRate", settings.homeLocRate);
qSettings->setValue("attRaw", settings.attRaw);
qSettings->setValue("attRawRate", settings.attRawRate);
qSettings->setValue("attActual", settings.attActual);
qSettings->setValue("attActHW", settings.attActHW);
qSettings->setValue("attActSim", settings.attActSim);
qSettings->setValue("attActCalc", settings.attActCalc);
qSettings->setValue("sonarAltitude", settings.sonarAltitude);
qSettings->setValue("sonarMaxAlt", settings.sonarMaxAlt);
qSettings->setValue("sonarAltRate", settings.sonarAltRate);
qSettings->setValue("gpsPosition", settings.gpsPosition);
qSettings->setValue("gpsPosRate", settings.gpsPosRate);
qSettings->setValue("inputCommand", settings.inputCommand);
qSettings->setValue("gcsReciever", settings.gcsReciever);
qSettings->setValue("manualControl", settings.manualControl);
qSettings->setValue("manualOutput", settings.manualOutput);
qSettings->setValue("outputRate", settings.outputRate);
}

View File

@ -0,0 +1,61 @@
/**
******************************************************************************
*
* @file hitlconfiguration.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2CONFIGURATION_H
#define HITLV2CONFIGURATION_H
#include <coreplugin/iuavgadgetconfiguration.h>
#include <QtGui/QColor>
#include <QString>
#include <simulatorv2.h>
using namespace Core;
class HITLConfiguration : public IUAVGadgetConfiguration
{
Q_OBJECT
Q_PROPERTY(SimulatorSettings settings READ Settings WRITE setSimulatorSettings)
public:
explicit HITLConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0);
void saveConfig(QSettings* settings) const;
IUAVGadgetConfiguration *clone();
SimulatorSettings Settings() const { return settings; }
public slots:
void setSimulatorSettings (const SimulatorSettings& params ) { settings = params; }
private:
SimulatorSettings settings;
};
#endif // HITLV2CONFIGURATION_H

View File

@ -0,0 +1,58 @@
/**
******************************************************************************
*
* @file hitlfactory.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2factory.h"
#include "hitlv2widget.h"
#include "hitlv2gadget.h"
#include "hitlv2configuration.h"
#include "hitlv2optionspage.h"
#include <coreplugin/iuavgadget.h>
HITLFactory::HITLFactory(QObject *parent)
: IUAVGadgetFactory(QString("HITLv2"), tr("HITL Simulation (v2)"), parent)
{
}
HITLFactory::~HITLFactory()
{
}
Core::IUAVGadget* HITLFactory::createGadget(QWidget *parent)
{
HITLWidget* gadgetWidget = new HITLWidget(parent);
return new HITLGadget(QString("HITLv2"), gadgetWidget, parent);
}
IUAVGadgetConfiguration *HITLFactory::createConfiguration(QSettings* qSettings)
{
return new HITLConfiguration(QString("HITLv2"), qSettings);
}
IOptionsPage *HITLFactory::createOptionsPage(IUAVGadgetConfiguration *config)
{
return new HITLOptionsPage(qobject_cast<HITLConfiguration*>(config));
}

View File

@ -0,0 +1,52 @@
/**
******************************************************************************
*
* @file hitlfactory.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2FACTORY_H
#define HITLV2FACTORY_H
#include <coreplugin/iuavgadgetfactory.h>
namespace Core {
class IUAVGadget;
class IUAVGadgetFactory;
}
using namespace Core;
class HITLFactory : public Core::IUAVGadgetFactory
{
Q_OBJECT
public:
HITLFactory(QObject *parent = 0);
~HITLFactory();
IUAVGadget *createGadget(QWidget *parent);
IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings);
IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config);
};
#endif // HITLV2FACTORY_H

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
*
* @file hitl.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2gadget.h"
#include "hitlv2widget.h"
#include "hitlv2configuration.h"
#include "simulatorv2.h"
HITLGadget::HITLGadget(QString classId, HITLWidget *widget, QWidget *parent) :
IUAVGadget(classId, parent),
m_widget(widget)
{
connect(this, SIGNAL(changeConfiguration(void)), m_widget, SLOT(stopButtonClicked(void)));
}
HITLGadget::~HITLGadget()
{
delete m_widget;
}
void HITLGadget::loadConfiguration(IUAVGadgetConfiguration* config)
{
HITLConfiguration *m = qobject_cast<HITLConfiguration*>(config);
emit changeConfiguration();
m_widget->setSettingParameters(m->Settings());
}

View File

@ -0,0 +1,60 @@
/**
******************************************************************************
*
* @file hitl.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2_H
#define HITLV2_H
#include <coreplugin/iuavgadget.h>
#include "hitlv2widget.h"
class IUAVGadget;
class QWidget;
class QString;
class Simulator;
using namespace Core;
class HITLGadget : public Core::IUAVGadget
{
Q_OBJECT
public:
HITLGadget(QString classId, HITLWidget *widget, QWidget *parent = 0);
~HITLGadget();
QWidget *widget() { return m_widget; }
void loadConfiguration(IUAVGadgetConfiguration* config);
signals:
void changeConfiguration();
private:
HITLWidget* m_widget;
Simulator* simulator;
};
#endif // HITLV2_H

View File

@ -0,0 +1,146 @@
/**
******************************************************************************
*
* @file hitloptionspage.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2optionspage.h"
#include "hitlv2configuration.h"
#include "ui_hitlv2optionspage.h"
#include "hitlv2plugin.h"
#include <QFileDialog>
#include <QtAlgorithms>
#include <QStringList>
#include "simulatorv2.h"
HITLOptionsPage::HITLOptionsPage(HITLConfiguration *conf, QObject *parent) :
IOptionsPage(parent),
config(conf)
{
}
QWidget *HITLOptionsPage::createPage(QWidget *parent)
{
// qDebug() << "HITLOptionsPage::createPage";
// Create page
m_optionsPage = new Ui::HITLOptionsPage();
QWidget* optionsPageWidget = new QWidget;
m_optionsPage->setupUi(optionsPageWidget);
int index = 0;
foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators)
m_optionsPage->chooseFlightSimulator->insertItem(index++, creator->Description(), creator->ClassId());
m_optionsPage->executablePath->setExpectedKind(Utils::PathChooser::File);
m_optionsPage->executablePath->setPromptDialogTitle(tr("Choose flight simulator executable"));
m_optionsPage->dataPath->setExpectedKind(Utils::PathChooser::Directory);
m_optionsPage->dataPath->setPromptDialogTitle(tr("Choose flight simulator data directory"));
// Restore the contents from the settings:
foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators) {
QString id = config->Settings().simulatorId;
if (creator->ClassId() == id)
m_optionsPage->chooseFlightSimulator->setCurrentIndex(HITLPlugin::typeSimulators.indexOf(creator));
}
m_optionsPage->hostAddress->setText(config->Settings().hostAddress);
m_optionsPage->inputPort->setText(QString::number(config->Settings().inPort));
m_optionsPage->remoteAddress->setText(config->Settings().remoteAddress);
m_optionsPage->outputPort->setText(QString::number(config->Settings().outPort));
m_optionsPage->executablePath->setPath(config->Settings().binPath);
m_optionsPage->dataPath->setPath(config->Settings().dataPath);
m_optionsPage->homeLocation->setChecked(config->Settings().homeLocation);
m_optionsPage->homeLocRate->setValue(config->Settings().homeLocRate);
m_optionsPage->attRaw->setChecked(config->Settings().attRaw);
m_optionsPage->attRawRate->setValue(config->Settings().attRawRate);
m_optionsPage->attActual->setChecked(config->Settings().attActual);
m_optionsPage->attActHW->setChecked(config->Settings().attActHW);
m_optionsPage->attActSim->setChecked(config->Settings().attActSim);
m_optionsPage->attActCalc->setChecked(config->Settings().attActCalc);
m_optionsPage->sonarAltitude->setChecked(config->Settings().sonarAltitude);
m_optionsPage->sonarMaxAlt->setValue(config->Settings().sonarMaxAlt);
m_optionsPage->sonarAltRate->setValue(config->Settings().sonarAltRate);
m_optionsPage->gpsPosition->setChecked(config->Settings().gpsPosition);
m_optionsPage->gpsPosRate->setValue(config->Settings().gpsPosRate);
m_optionsPage->inputCommand->setChecked(config->Settings().inputCommand);
m_optionsPage->gcsReciever->setChecked(config->Settings().gcsReciever);
m_optionsPage->manualControl->setChecked(config->Settings().manualControl);
m_optionsPage->manualOutput->setChecked(config->Settings().manualOutput);
m_optionsPage->outputRate->setValue(config->Settings().outputRate);
return optionsPageWidget;
}
void HITLOptionsPage::apply()
{
SimulatorSettings settings;
int i = m_optionsPage->chooseFlightSimulator->currentIndex();
settings.simulatorId = m_optionsPage->chooseFlightSimulator->itemData(i).toString();
settings.hostAddress = m_optionsPage->hostAddress->text();
settings.inPort = m_optionsPage->inputPort->text().toInt();
settings.remoteAddress = m_optionsPage->remoteAddress->text();
settings.outPort = m_optionsPage->outputPort->text().toInt();
settings.binPath = m_optionsPage->executablePath->path();
settings.dataPath = m_optionsPage->dataPath->path();
settings.homeLocation = m_optionsPage->homeLocation->isChecked();
settings.homeLocRate = m_optionsPage->homeLocRate->value();
settings.attRaw = m_optionsPage->attRaw->isChecked();
settings.attRawRate = m_optionsPage->attRawRate->value();
settings.attActual = m_optionsPage->attActual->isChecked();
settings.attActHW = m_optionsPage->attActHW->isChecked();
settings.attActSim = m_optionsPage->attActSim->isChecked();
settings.attActCalc = m_optionsPage->attActCalc->isChecked();
settings.sonarAltitude = m_optionsPage->sonarAltitude->isChecked();
settings.sonarMaxAlt = m_optionsPage->sonarMaxAlt->value();
settings.sonarAltRate = m_optionsPage->sonarAltRate->value();
settings.gpsPosition = m_optionsPage->gpsPosition->isChecked();
settings.gpsPosRate = m_optionsPage->gpsPosRate->value();
settings.inputCommand = m_optionsPage->inputCommand->isChecked();
settings.gcsReciever = m_optionsPage->gcsReciever->isChecked();
settings.manualControl = m_optionsPage->manualControl->isChecked();
settings.manualOutput = m_optionsPage->manualOutput->isChecked();
settings.outputRate = m_optionsPage->outputRate->value();
config->setSimulatorSettings(settings);
}
void HITLOptionsPage::finish()
{
delete m_optionsPage;
}

View File

@ -0,0 +1,61 @@
/**
******************************************************************************
*
* @file hitloptionspage.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2OPTIONSPAGE_H
#define HITLV2OPTIONSPAGE_H
#include <coreplugin/dialogs/ioptionspage.h>
namespace Core {
class IUAVGadgetConfiguration;
}
class HITLConfiguration;
using namespace Core;
namespace Ui {
class HITLOptionsPage;
}
class HITLOptionsPage : public IOptionsPage
{
Q_OBJECT
public:
explicit HITLOptionsPage(HITLConfiguration *conf, QObject *parent = 0);
QWidget *createPage(QWidget *parent);
void apply();
void finish();
bool isDecorated() const { return true; }
private:
HITLConfiguration* config;
Ui::HITLOptionsPage* m_optionsPage;
};
#endif // HITLV2OPTIONSPAGE_H

View File

@ -0,0 +1,639 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>HITLOptionsPage</class>
<widget class="QWidget" name="HITLOptionsPage">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>403</width>
<height>400</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>Choose flight simulator:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="chooseFlightSimulator"/>
</item>
</layout>
</item>
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label_6">
<property name="text">
<string>Local interface (IP):</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="hostAddress">
<property name="toolTip">
<string>For communication with sim computer via network. Should be the IP address of one of the interfaces of the GCS computer.</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_9">
<property name="text">
<string>Remote interface (IP):</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="remoteAddress">
<property name="toolTip">
<string>Only required if running simulator on remote machine. Should be the IP of the machine on which the simulator is running.</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_5">
<property name="text">
<string>Input Port:</string>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLineEdit" name="inputPort">
<property name="toolTip">
<string>For receiving data from sim</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Output Port:</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLineEdit" name="outputPort">
<property name="toolTip">
<string>For sending data to sim</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QFormLayout" name="formLayout">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Path executable:</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="Utils::PathChooser" name="executablePath" native="true"/>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Data directory:</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="Utils::PathChooser" name="dataPath" native="true"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Attitude data</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QGroupBox" name="attRaw">
<property name="title">
<string>AttitudeRaw (gyro, accels)</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_8">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="attRawRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>10</number>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="attActual">
<property name="title">
<string>AttitudeActual</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QRadioButton" name="attActHW">
<property name="text">
<string>send raw data to board</string>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="attActSim">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string/>
</property>
<property name="text">
<string>use values from simulator</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="attActCalc">
<property name="toolTip">
<string/>
</property>
<property name="text">
<string>calculate from AttitudeRaw</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string>Other data</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>3</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QGroupBox" name="homeLocation">
<property name="title">
<string>HomeLocation</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="homeLocRate">
<property name="toolTip">
<string>0 - update once, or every N seconds</string>
</property>
<property name="suffix">
<string>sec</string>
</property>
<property name="maximum">
<number>10</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="gpsPosition">
<property name="title">
<string>GPSPosition</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_10">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="gpsPosRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>100</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="value">
<number>500</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="sonarAltitude">
<property name="title">
<string>SonarAltitude</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_6">
<property name="spacing">
<number>3</number>
</property>
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="label_11">
<property name="text">
<string>Range detectioon</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QSpinBox" name="sonarMaxAlt">
<property name="suffix">
<string>m</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>10</number>
</property>
<property name="value">
<number>5</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_12">
<property name="text">
<string>Refresh rate</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSpinBox" name="sonarAltRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>20</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="inputCommand">
<property name="title">
<string>Map command from simulator</string>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_5">
<property name="spacing">
<number>3</number>
</property>
<property name="topMargin">
<number>3</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<widget class="QRadioButton" name="gcsReciever">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>to GCSReciver</string>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QRadioButton" name="manualControl">
<property name="enabled">
<bool>false</bool>
</property>
<property name="text">
<string>to ManualCtrll (not implemented)</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6">
<property name="spacing">
<number>6</number>
</property>
<item>
<widget class="QCheckBox" name="manualOutput">
<property name="text">
<string>Maximum output rate</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="outputRate">
<property name="suffix">
<string>ms</string>
</property>
<property name="minimum">
<number>10</number>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>5</number>
</property>
<property name="value">
<number>15</number>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>Utils::PathChooser</class>
<extends>QWidget</extends>
<header>utils/pathchooser.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<tabstops>
<tabstop>chooseFlightSimulator</tabstop>
<tabstop>hostAddress</tabstop>
<tabstop>inputPort</tabstop>
<tabstop>remoteAddress</tabstop>
<tabstop>outputPort</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>

View File

@ -0,0 +1,70 @@
/**
******************************************************************************
*
* @file mapplugin.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2plugin.h"
#include "hitlv2factory.h"
#include <QtPlugin>
#include <QStringList>
#include <extensionsystem/pluginmanager.h>
#include "aerosimrc.h"
QList<SimulatorCreator* > HITLPlugin::typeSimulators;
HITLPlugin::HITLPlugin()
{
// Do nothing
}
HITLPlugin::~HITLPlugin()
{
// Do nothing
}
bool HITLPlugin::initialize(const QStringList& args, QString *errMsg)
{
Q_UNUSED(args);
Q_UNUSED(errMsg);
mf = new HITLFactory(this);
addAutoReleasedObject(mf);
addSimulator(new AeroSimRCSimulatorCreator("ASimRC", "AeroSimRC"));
return true;
}
void HITLPlugin::extensionsInitialized()
{
// Do nothing
}
void HITLPlugin::shutdown()
{
// Do nothing
}
Q_EXPORT_PLUGIN(HITLPlugin)

View File

@ -0,0 +1,67 @@
/**
******************************************************************************
*
* @file browserplugin.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2PLUGIN_H
#define HITLV2PLUGIN_H
#include <extensionsystem/iplugin.h>
#include <QStringList>
#include <simulatorv2.h>
class HITLFactory;
class HITLPlugin : public ExtensionSystem::IPlugin
{
public:
HITLPlugin();
~HITLPlugin();
void extensionsInitialized();
bool initialize(const QStringList & arguments, QString * errorString);
void shutdown();
static void addSimulator(SimulatorCreator* creator)
{
HITLPlugin::typeSimulators.append(creator);
}
static SimulatorCreator* getSimulatorCreator(const QString classId)
{
foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) {
if(classId == creator->ClassId())
return creator;
}
return 0;
}
static QList<SimulatorCreator* > typeSimulators;
private:
HITLFactory *mf;
};
#endif /* HITLV2PLUGIN_H */

View File

@ -0,0 +1,187 @@
/**
******************************************************************************
*
* @file hitlwidget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "hitlv2widget.h"
#include "ui_hitlv2widget.h"
#include <QDebug>
#include <QFile>
#include <QDir>
#include <QDateTime>
#include <QThread>
#include "hitlv2plugin.h"
#include "simulatorv2.h"
#include "uavobjectmanager.h"
#include <coreplugin/icore.h>
#include <coreplugin/threadmanager.h>
QStringList Simulator::instances;
HITLWidget::HITLWidget(QWidget *parent)
: QWidget(parent),
simulator(0)
{
widget = new Ui_HITLWidget();
widget->setupUi(this);
widget->startButton->setEnabled(true);
widget->stopButton->setEnabled(false);
strAutopilotDisconnected = " AP OFF ";
strSimulatorDisconnected = " Sim OFF ";
strAutopilotConnected = " AP ON ";
// strSimulatorConnected = " Sim ON ";
strStyleEnable = "QFrame{background-color: green; color: white}";
strStyleDisable = "QFrame{background-color: red; color: grey}";
widget->apLabel->setText(strAutopilotDisconnected);
widget->simLabel->setText(strSimulatorDisconnected);
connect(widget->startButton, SIGNAL(clicked()), this, SLOT(startButtonClicked()));
connect(widget->stopButton, SIGNAL(clicked()), this, SLOT(stopButtonClicked()));
connect(widget->buttonClearLog, SIGNAL(clicked()), this, SLOT(buttonClearLogClicked()));
}
HITLWidget::~HITLWidget()
{
delete widget;
}
void HITLWidget::startButtonClicked()
{
// allow only one instance per simulator
if (Simulator::Instances().indexOf(settings.simulatorId) != -1) {
widget->textBrowser->append(settings.simulatorId + " alreary started!");
return;
}
if (!HITLPlugin::typeSimulators.size()) {
widget->textBrowser->append("There is no registered simulators, add through HITLPlugin::addSimulator");
return;
}
// Stop running process if one is active
if (simulator) {
QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection);
simulator = NULL;
}
if (settings.hostAddress == "" || settings.inPort == 0) {
widget->textBrowser->append("Before start, set UDP parameters in options page!");
return;
}
SimulatorCreator* creator = HITLPlugin::getSimulatorCreator(settings.simulatorId);
simulator = creator->createSimulator(settings);
simulator->setName(creator->Description());
simulator->setSimulatorId(creator->ClassId());
connect(simulator, SIGNAL(processOutput(QString)), this, SLOT(onProcessOutput(QString)));
// Setup process
onProcessOutput(QString("[%1] Starting %2... ")
.arg(QTime::currentTime().toString("hh:mm:ss"))
.arg(creator->Description()));
// Start bridge
bool ret = QMetaObject::invokeMethod(simulator, "setupProcess", Qt::QueuedConnection);
if (ret) {
Simulator::setInstance(settings.simulatorId);
connect(this, SIGNAL(deleteSimulator()), simulator, SLOT(onDeleteSimulator()), Qt::QueuedConnection);
widget->startButton->setEnabled(false);
widget->stopButton->setEnabled(true);
connect(simulator, SIGNAL(autopilotConnected()), this, SLOT(onAutopilotConnect()), Qt::QueuedConnection);
connect(simulator, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect()), Qt::QueuedConnection);
connect(simulator, SIGNAL(simulatorConnected()), this, SLOT(onSimulatorConnect()), Qt::QueuedConnection);
connect(simulator, SIGNAL(simulatorDisconnected()), this, SLOT(onSimulatorDisconnect()), Qt::QueuedConnection);
// Initialize connection status
if (simulator->isAutopilotConnected())
onAutopilotConnect();
else
onAutopilotDisconnect();
if (simulator->isSimulatorConnected())
onSimulatorConnect();
else
onSimulatorDisconnect();
}
}
void HITLWidget::stopButtonClicked()
{
if (simulator)
widget->textBrowser->append(QString("[%1] Terminate %2 ")
.arg(QTime::currentTime().toString("hh:mm:ss"))
.arg(simulator->Name()));
widget->startButton->setEnabled(true);
widget->stopButton->setEnabled(false);
widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}"));
widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}"));
widget->apLabel->setText(strAutopilotDisconnected);
widget->simLabel->setText(strSimulatorDisconnected);
if (simulator) {
QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection);
simulator = NULL;
}
}
void HITLWidget::buttonClearLogClicked()
{
widget->textBrowser->clear();
}
void HITLWidget::onProcessOutput(QString text)
{
widget->textBrowser->append(text);
}
void HITLWidget::onAutopilotConnect()
{
widget->apLabel->setStyleSheet(strStyleEnable);
widget->apLabel->setText(strAutopilotConnected);
}
void HITLWidget::onAutopilotDisconnect()
{
widget->apLabel->setStyleSheet(strStyleDisable);
widget->apLabel->setText(strAutopilotDisconnected);
}
void HITLWidget::onSimulatorConnect()
{
widget->simLabel->setStyleSheet(strStyleEnable);
widget->simLabel->setText(" " + simulator->Name() + " ON ");
}
void HITLWidget::onSimulatorDisconnect()
{
widget->simLabel->setStyleSheet(strStyleDisable);
widget->simLabel->setText(" " + simulator->Name() + " OFF ");
}

View File

@ -0,0 +1,72 @@
/**
******************************************************************************
*
* @file hitlwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef HITLV2WIDGET_H
#define HITLV2WIDGET_H
#include <QtGui/QWidget>
#include <QProcess>
#include "simulatorv2.h"
class Ui_HITLWidget;
class HITLWidget : public QWidget
{
Q_OBJECT
public:
HITLWidget(QWidget *parent = 0);
~HITLWidget();
void setSettingParameters(const SimulatorSettings& params) { settings = params; }
signals:
void deleteSimulator();
private slots:
void startButtonClicked();
void stopButtonClicked();
void buttonClearLogClicked();
void onProcessOutput(QString text);
void onAutopilotConnect();
void onAutopilotDisconnect();
void onSimulatorConnect();
void onSimulatorDisconnect();
private:
Ui_HITLWidget* widget;
Simulator* simulator;
SimulatorSettings settings;
QString strAutopilotDisconnected;
QString strSimulatorDisconnected;
QString strAutopilotConnected;
// QString strSimulatorConnected;
QString strStyleEnable;
QString strStyleDisable;
};
#endif /* HITLV2WIDGET_H */

View File

@ -0,0 +1,314 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>HITLWidget</class>
<widget class="QWidget" name="HITLWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>477</width>
<height>300</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<property name="styleSheet">
<string notr="true">
QScrollBar:vertical {
border: 1px solid grey;
background: grey;
margin: 22px 0 22px 0;
}
QScrollBar:vertical:disabled {
border: 1px solid grey;
background-color: grey;
margin: 22px 0 22px 0;
}
QScrollBar::handle:vertical {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 255, 255), stop:1 rgba(80, 80, 160, 255));
min-height: 20px;
}
QScrollBar::handle:vertical:disabled{
background-color: grey;
min-height: 20px;
}
QScrollBar::handle:vertical:pressed {
background-color: rgb(85, 85, 255);
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(170, 170, 255, 255), stop:1 rgba(80, 80, 160, 255));
min-height: 20px;
}
QScrollBar::add-line:vertical {
border: 1px solid black;
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
height: 20px;
subcontrol-position: bottom;
subcontrol-origin: margin;
}
QScrollBar::add-line:vertical:disabled {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255));
border: 1px solid grey;
}
QScrollBar::sub-line:vertical:disabled {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255));
border: 1px solid grey;
}
QScrollBar::add-line:vertical:pressed {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200));
}
QScrollBar::sub-line:vertical:pressed {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200));
}
QScrollBar::sub-line:vertical {
border: 1px solid black;
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
height: 20px;
subcontrol-position: top;
subcontrol-origin: margin;
}
QScrollBar::down-arrow:vertical {
image: url(:/hitlnew/images/arrow-down2.png);
}
QScrollBar::up-arrow:vertical {
image: url(:/hitlnew/images/arrow-up2.png);
}
QScrollBar::add-page:vertical, QScrollBar::sub-page:vertical {
background: none;
}
QPushButton {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255));
color: rgb(255, 255, 255);
border: 1px solid black;
width: 66px;
height: 20px;
}
QPushButton:disabled {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 120, 255));
color: rgb(194, 194, 194);
border: 1px solid gray;
width: 66px;
height: 20px;
}
QPushButton:hover {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200));
color: rgb(255, 255, 255);
border: 0px;
}
QPushButton:pressed {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
color: rgb(255, 255, 255);
border: 0px;
}
QPushButton:checked {
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255));
color: rgb(255, 255, 255);
border: 0px;
}</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QFrame" name="frame">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">
QFrame{
background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255));
color: rgba(0, 0, 0, 128);
}
</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<property name="sizeConstraint">
<enum>QLayout::SetMaximumSize</enum>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
<item>
<widget class="QPushButton" name="startButton">
<property name="toolTip">
<string>Request update</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Start</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="stopButton">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Send update</string>
</property>
<property name="text">
<string>Stop</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="apLabel">
<property name="minimumSize">
<size>
<width>0</width>
<height>22</height>
</size>
</property>
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">color: rgb(255, 255, 255);</string>
</property>
<property name="text">
<string>AP OFF</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="simLabel">
<property name="minimumSize">
<size>
<width>0</width>
<height>22</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">color: rgb(255, 255, 255);</string>
</property>
<property name="text">
<string>Sim OFF</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="buttonClearLog">
<property name="text">
<string>Clear Log</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QTextEdit" name="textBrowser">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">QTextEdit {
background-color: white;
color: rgb(0, 0, 0);
}</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOn</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>

View File

@ -0,0 +1,341 @@
/**
******************************************************************************
*
* @file simulator.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "simulatorv2.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/icore.h>
#include <coreplugin/threadmanager.h>
volatile bool Simulator::isStarted = false;
const float Simulator::GEE = 9.81;
const float Simulator::FT2M = 0.3048;
const float Simulator::KT2MPS = 0.514444444;
const float Simulator::INHG2KPA = 3.386;
const float Simulator::FPS2CMPS = 30.48;
const float Simulator::DEG2RAD = (M_PI/180.0);
const float Simulator::RAD2DEG = (180.0/M_PI);
Simulator::Simulator(const SimulatorSettings& params) :
inSocket(NULL),
outSocket(NULL),
settings(params),
updatePeriod(50),
simTimeout(2000),
autopilotConnectionStatus(false),
simConnectionStatus(false),
txTimer(NULL),
simTimer(NULL),
name("")
{
// move to thread
moveToThread(Core::ICore::instance()->threadManager()->getRealTimeThread());
connect(this, SIGNAL(myStart()), this, SLOT(onStart()), Qt::QueuedConnection);
emit myStart();
}
Simulator::~Simulator()
{
// qDebug() << "Simulator::~Simulator";
if (inSocket) {
delete inSocket;
inSocket = NULL;
}
if (outSocket) {
delete outSocket;
outSocket = NULL;
}
if (txTimer) {
delete txTimer;
txTimer = NULL;
}
if (simTimer) {
delete simTimer;
simTimer = NULL;
}
}
void Simulator::onDeleteSimulator(void)
{
// qDebug() << "Simulator::onDeleteSimulator";
resetAllObjects();
Simulator::setStarted(false);
Simulator::Instances().removeOne(simulatorId);
disconnect(this);
delete this;
}
void Simulator::onStart()
{
// qDebug() << "Simulator::onStart";
QMutexLocker locker(&lock);
// Get required UAVObjects
ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager* objManager = pm->getObject<UAVObjectManager>();
// actDesired = ActuatorDesired::GetInstance(objManager);
// manCtrlCommand = ManualControlCommand::GetInstance(objManager);
// velActual = VelocityActual::GetInstance(objManager);
// posActual = PositionActual::GetInstance(objManager);
// altActual = BaroAltitude::GetInstance(objManager);
// camDesired = CameraDesired::GetInstance(objManager);
// acsDesired = AccessoryDesired::GetInstance(objManager);
posHome = HomeLocation::GetInstance(objManager);
accels = Accels::GetInstance(objManager);
gyros = Gyros::GetInstance(objManager);
attActual = AttitudeActual::GetInstance(objManager);
gpsPosition = GPSPosition::GetInstance(objManager);
flightStatus = FlightStatus::GetInstance(objManager);
gcsReceiver = GCSReceiver::GetInstance(objManager);
actCommand = ActuatorCommand::GetInstance(objManager);
attSettings = AttitudeSettings::GetInstance(objManager);
sonarAlt = SonarAltitude::GetInstance(objManager);
telStats = GCSTelemetryStats::GetInstance(objManager);
// Listen to autopilot connection events
TelemetryManager* telMngr = pm->getObject<TelemetryManager>();
connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect()));
connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect()));
// If already connect setup autopilot
GCSTelemetryStats::DataFields stats = telStats->getData();
if (stats.Status == GCSTelemetryStats::STATUS_CONNECTED)
onAutopilotConnect();
emit processOutput("Local interface: " + settings.hostAddress + ":" + \
QString::number(settings.inPort) + "\n" + \
"Remote interface: " + settings.remoteAddress + ":" + \
QString::number(settings.outPort) + "\n");
inSocket = new QUdpSocket();
outSocket = new QUdpSocket();
setupUdpPorts(settings.hostAddress, settings.inPort, settings.outPort);
connect(inSocket, SIGNAL(readyRead()), this, SLOT(receiveUpdate())/*, Qt::DirectConnection*/);
// Setup transmit timer
if (settings.manualOutput) {
txTimer = new QTimer();
connect(txTimer, SIGNAL(timeout()), this, SLOT(transmitUpdate())/*, Qt::DirectConnection*/);
txTimer->setInterval(settings.outputRate);
txTimer->start();
}
// Setup simulator connection timer
simTimer = new QTimer();
connect(simTimer, SIGNAL(timeout()), this, SLOT(onSimulatorConnectionTimeout())/*, Qt::DirectConnection*/);
simTimer->setInterval(simTimeout);
simTimer->start();
#ifdef DBG_TIMERS
timeRX = QTime();
timeRX.start();
timeTX = QTime();
timeTX.start();
#endif
setupObjects();
}
void Simulator::receiveUpdate()
{
// Update connection timer and status
simTimer->start();
if (!simConnectionStatus) {
simConnectionStatus = true;
emit simulatorConnected();
}
// Process data
while (inSocket->hasPendingDatagrams()) {
// Receive datagram
QByteArray datagram;
datagram.resize(inSocket->pendingDatagramSize());
QHostAddress sender;
quint16 senderPort;
inSocket->readDatagram(datagram.data(), datagram.size(), &sender, &senderPort);
// Process incomming data
processUpdate(datagram);
}
if (!settings.manualOutput)
transmitUpdate();
}
void Simulator::setupObjects()
{
if (settings.gcsReciever) {
setupInputObject(actCommand, settings.outputRate);
setupOutputObject(gcsReceiver);
} else if (settings.manualControl) {
// setupInputObject(actDesired);
// setupInputObject(camDesired);
// setupInputObject(acsDesired);
// setupOutputObject(manCtrlCommand);
qDebug() << "ManualControlCommand not implemented yet";
}
if (settings.homeLocation)
setupOutputObject(posHome);
if (settings.sonarAltitude)
setupOutputObject(sonarAlt);
if (settings.gpsPosition)
setupOutputObject(gpsPosition);
if (settings.attRaw || settings.attActual) {
setupOutputObject(accels);
setupOutputObject(gyros);
}
if (settings.attActual && !settings.attActHW)
setupOutputObject(attActual);
else
setupWatchedObject(attActual);
}
void Simulator::resetAllObjects()
{
setupDefaultObject(posHome);
setupDefaultObject(accels);
setupDefaultObject(gyros);
setupDefaultObject(attActual);
setupDefaultObject(gpsPosition);
setupDefaultObject(gcsReceiver);
setupDefaultObject(actCommand);
setupDefaultObject(sonarAlt);
// setupDefaultObject(manCtrlCommand);
// setupDefaultObject(actDesired);
// setupDefaultObject(camDesired);
// setupDefaultObject(acsDesired);
// setupDefaultObject(altActual);
// setupDefaultObject(posActual);
// setupDefaultObject(velActual);
}
void Simulator::setupInputObject(UAVObject* obj, quint32 updateRate)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY);
UAVObject::SetGcsTelemetryAcked(mdata, false);
UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL);
mdata.gcsTelemetryUpdatePeriod = 0;
UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE);
UAVObject::SetFlightTelemetryAcked(mdata, false);
if (settings.manualOutput) {
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = updateRate;
} else {
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE);
mdata.flightTelemetryUpdatePeriod = 0;
}
obj->setMetadata(mdata);
}
void Simulator::setupWatchedObject(UAVObject *obj)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY);
UAVObject::SetGcsTelemetryAcked(mdata, false);
UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL);
mdata.gcsTelemetryUpdatePeriod = 0;
UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE);
UAVObject::SetFlightTelemetryAcked(mdata, false);
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
mdata.flightTelemetryUpdatePeriod = 100;
obj->setMetadata(mdata);
}
void Simulator::setupOutputObject(UAVObject* obj)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE);
UAVObject::SetGcsTelemetryAcked(mdata, false);
UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE);
mdata.gcsTelemetryUpdatePeriod = 0;
UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY);
UAVObject::SetFlightTelemetryAcked(mdata, false);
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL);
mdata.flightTelemetryUpdatePeriod = 0;
obj->setMetadata(mdata);
}
void Simulator::setupDefaultObject(UAVObject *obj)
{
UAVObject::Metadata mdata;
mdata = obj->getDefaultMetadata();
obj->setMetadata(mdata);
}
void Simulator::onAutopilotConnect()
{
autopilotConnectionStatus = true;
emit autopilotConnected();
}
void Simulator::onAutopilotDisconnect()
{
autopilotConnectionStatus = false;
emit autopilotDisconnected();
}
void Simulator::onSimulatorConnectionTimeout()
{
if (simConnectionStatus) {
simConnectionStatus = false;
emit simulatorDisconnected();
}
}
void Simulator::telStatsUpdated(UAVObject* obj)
{
GCSTelemetryStats::DataFields stats = telStats->getData();
if (!autopilotConnectionStatus && stats.Status == GCSTelemetryStats::STATUS_CONNECTED)
onAutopilotConnect();
else if (autopilotConnectionStatus && stats.Status != GCSTelemetryStats::STATUS_CONNECTED)
onAutopilotDisconnect();
}

View File

@ -0,0 +1,222 @@
/**
******************************************************************************
*
* @file simulator.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup HITLPlugin HITL Plugin
* @{
* @brief The Hardware In The Loop plugin
*****************************************************************************/
/*
* 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
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef ISIMULATORV2_H
#define ISIMULATORV2_H
#include <QObject>
#include <QUdpSocket>
#include <QTimer>
#include <QProcess>
#include <QScopedPointer>
#include <qmath.h>
#include "uavtalk/telemetrymanager.h"
#include "uavobjectmanager.h"
#include "homelocation.h"
#include "accels.h"
#include "gyros.h"
#include "attitudeactual.h"
#include "gpsposition.h"
#include "flightstatus.h"
#include "gcsreceiver.h"
#include "actuatorcommand.h"
#include "gcstelemetrystats.h"
#include "attitudesettings.h"
#include "sonaraltitude.h"
//#define DBG_TIMERS
#undef DBG_TIMERS
/**
* just imagine this was a class without methods and all public properties
*/
typedef struct _CONNECTION
{
QString simulatorId;
QString hostAddress;
int inPort;
QString remoteAddress;
int outPort;
QString binPath;
QString dataPath;
bool homeLocation;
quint16 homeLocRate;
bool attRaw;
quint8 attRawRate;
bool attActual;
bool attActHW;
bool attActSim;
bool attActCalc;
bool sonarAltitude;
float sonarMaxAlt;
quint16 sonarAltRate;
bool gpsPosition;
quint16 gpsPosRate;
bool inputCommand;
bool gcsReciever;
bool manualControl;
bool manualOutput;
quint8 outputRate;
} SimulatorSettings;
class Simulator : public QObject
{
Q_OBJECT
public:
Simulator(const SimulatorSettings& params);
virtual ~Simulator();
bool isAutopilotConnected() const { return autopilotConnectionStatus; }
bool isSimulatorConnected() const { return simConnectionStatus; }
QString Name() const { return name; }
void setName(QString str) { name = str; }
QString SimulatorId() const { return simulatorId; }
void setSimulatorId(QString str) { simulatorId = str; }
static bool IsStarted() { return isStarted; }
static void setStarted(bool val) { isStarted = val; }
static QStringList& Instances() { return Simulator::instances; }
static void setInstance(const QString& str) { Simulator::instances.append(str); }
virtual void stopProcess() {}
virtual void setupUdpPorts(const QString& host, int inPort, int outPort) { Q_UNUSED(host) Q_UNUSED(inPort) Q_UNUSED(outPort)}
signals:
void processOutput(QString str);
void autopilotConnected();
void autopilotDisconnected();
void simulatorConnected();
void simulatorDisconnected();
void myStart();
public slots:
Q_INVOKABLE virtual bool setupProcess() { return true; }
private slots:
void onStart();
void receiveUpdate();
void onAutopilotConnect();
void onAutopilotDisconnect();
void onSimulatorConnectionTimeout();
void telStatsUpdated(UAVObject* obj);
Q_INVOKABLE void onDeleteSimulator(void);
virtual void transmitUpdate() = 0;
virtual void processUpdate(const QByteArray& data) = 0;
protected:
static const float GEE;
static const float FT2M;
static const float KT2MPS;
static const float INHG2KPA;
static const float FPS2CMPS;
static const float DEG2RAD;
static const float RAD2DEG;
#ifdef DBG_TIMERS
QTime timeRX;
QTime timeTX;
#endif
QUdpSocket* inSocket;
QUdpSocket* outSocket;
// ActuatorDesired* actDesired;
// ManualControlCommand* manCtrlCommand;
// VelocityActual* velActual;
// PositionActual* posActual;
// BaroAltitude* altActual;
// CameraDesired *camDesired;
// AccessoryDesired *acsDesired;
Accels *accels;
Gyros *gyros;
AttitudeActual *attActual;
HomeLocation *posHome;
FlightStatus *flightStatus;
GPSPosition *gpsPosition;
GCSReceiver *gcsReceiver;
ActuatorCommand *actCommand;
AttitudeSettings *attSettings;
SonarAltitude *sonarAlt;
GCSTelemetryStats* telStats;
SimulatorSettings settings;
QMutex lock;
private:
int updatePeriod;
int simTimeout;
volatile bool autopilotConnectionStatus;
volatile bool simConnectionStatus;
QTimer* txTimer;
QTimer* simTimer;
QString name;
QString simulatorId;
volatile static bool isStarted;
static QStringList instances;
void setupObjects();
void resetAllObjects();
void setupInputObject(UAVObject* obj, quint32 updateRate);
void setupOutputObject(UAVObject* obj);
void setupWatchedObject(UAVObject *obj);
void setupDefaultObject(UAVObject *obj);
};
class SimulatorCreator
{
public:
SimulatorCreator(QString id, QString descr) :
classId(id),
description(descr)
{}
virtual ~SimulatorCreator() {}
QString ClassId() const { return classId; }
QString Description() const { return description; }
virtual Simulator* createSimulator(const SimulatorSettings& params) = 0;
private:
QString classId;
QString description;
};
#endif // ISIMULATORV2_H

View File

@ -256,7 +256,10 @@ void NotifyPluginOptionsPage::addDynamicField(UAVObjectField* objField)
_dynamicFieldCondition->removeItem(smaller);
_dynamicFieldCondition->removeItem(bigger);
}
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(_selectedNotification->getCondition())));
int cond=_selectedNotification->getCondition();
if(cond<0)
return;
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(cond)));
connect(_dynamicFieldCondition, SIGNAL(currentIndexChanged(QString)),
this, SLOT(on_changedIndex_rangeValue(QString)));
@ -434,8 +437,10 @@ void NotifyPluginOptionsPage::updateConfigView(NotificationItem* notification)
_optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText("default"));
_optionsPage->Sound3->setCurrentIndex(_optionsPage->Sound3->findText(notification->getSound3()));
}
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(notification->getCondition())));
int cond=notification->getCondition();
if(cond<0)
return;
_dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(cond)));
_sayOrder->setCurrentIndex(notification->getSayOrder());

View File

@ -158,6 +158,13 @@ plugin_hitlnew.depends += plugin_uavobjects
plugin_hitlnew.depends += plugin_uavtalk
SUBDIRS += plugin_hitlnew
#HITLNEW Simulation gadget v2
plugin_hitl_v2.subdir = hitlv2
plugin_hitl_v2.depends = plugin_coreplugin
plugin_hitl_v2.depends += plugin_uavobjects
plugin_hitl_v2.depends += plugin_uavtalk
SUBDIRS += plugin_hitl_v2
# Export and Import GCS Configuration
plugin_importexport.subdir = importexport
plugin_importexport.depends = plugin_coreplugin

View File

@ -35,6 +35,7 @@
#include <QEventLoop>
#include <QTimer>
#include <objectpersistence.h>
#include <firmwareiapobj.h>
// ******************************
// constructor/destructor
@ -199,25 +200,63 @@ void UAVObjectUtilManager::objectPersistenceOperationFailed()
*/
void UAVObjectUtilManager::objectPersistenceUpdated(UAVObject * obj)
{
qDebug() << "objectPersistenceUpdated: " << obj->getField("Operation")->getValue().toString();
Q_ASSERT(obj->getName().compare("ObjectPersistence") == 0);
if(saveState == AWAITING_COMPLETED) {
failureTimer.stop();
// Check flight is saying it completed. This is the only thing flight should do to trigger an update.
Q_ASSERT( obj->getField("Operation")->getValue().toString().compare(QString("Completed")) == 0 );
Q_ASSERT(obj);
Q_ASSERT(obj->getObjID() == ObjectPersistence::OBJID);
ObjectPersistence::DataFields objectPersistence = ((ObjectPersistence *)obj)->getData();
if(saveState == AWAITING_COMPLETED && objectPersistence.Operation == ObjectPersistence::OPERATION_ERROR) {
failureTimer.stop();
objectPersistenceOperationFailed();
} else if (saveState == AWAITING_COMPLETED &&
objectPersistence.Operation == ObjectPersistence::OPERATION_COMPLETED) {
failureTimer.stop();
// Check right object saved
UAVObject* savingObj = queue.head();
Q_ASSERT( obj->getField("ObjectID")->getValue() == savingObj->getObjID() );
if(objectPersistence.ObjectID != savingObj->getObjID() ) {
objectPersistenceOperationFailed();
return;
}
obj->disconnect(this);
queue.dequeue(); // We can now remove the object, it's done.
saveState = IDLE;
emit saveCompleted(obj->getField("ObjectID")->getValue().toInt(), true);
emit saveCompleted(objectPersistence.ObjectID, true);
saveNextObject();
}
}
/**
* Helper function that makes sure FirmwareIAP is updated and then returns the data
*/
FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap()
{
FirmwareIAPObj::DataFields dummy;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Q_ASSERT(pm);
if (!pm)
return dummy;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
Q_ASSERT(om);
if (!om)
return dummy;
FirmwareIAPObj *firmwareIap = FirmwareIAPObj::GetInstance(om);
Q_ASSERT(firmwareIap);
if (!firmwareIap)
return dummy;
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(firmwareIap, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
firmwareIap->requestUpdate();
loop.exec();
return firmwareIap->getData();
}
/**
* Get the UAV Board model, for anyone interested. Return format is:
@ -225,25 +264,8 @@ void UAVObjectUtilManager::objectPersistenceUpdated(UAVObject * obj)
*/
int UAVObjectUtilManager::getBoardModel()
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
int boardType = (obj->getField("BoardType")->getValue().toInt()) << 8;
boardType += obj->getField("BoardRevision")->getValue().toInt();
return boardType;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
return (firmwareIapData.BoardType << 8) + firmwareIapData.BoardRevision;
}
/**
@ -252,54 +274,18 @@ int UAVObjectUtilManager::getBoardModel()
QByteArray UAVObjectUtilManager::getBoardCPUSerial()
{
QByteArray cpuSerial;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
for (int i = 0; i < FirmwareIAPObj::CPUSERIAL_NUMELEM; i++)
cpuSerial.append(firmwareIapData.CPUSerial[i]);
UAVObjectField* cpuField = obj->getField("CPUSerial");
for (uint i = 0; i < cpuField->getNumElements(); ++i) {
cpuSerial.append(cpuField->getValue(i).toUInt());
}
return cpuSerial;
}
quint32 UAVObjectUtilManager::getFirmwareCRC()
{
quint32 fwCRC;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
obj->getField("crc")->setValue(0);
obj->updated();
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
UAVObjectField* fwCRCField = obj->getField("crc");
fwCRC=(quint32)fwCRCField->getValue().toLongLong();
return fwCRC;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
return firmwareIapData.crc;
}
/**
@ -308,27 +294,11 @@ quint32 UAVObjectUtilManager::getFirmwareCRC()
QByteArray UAVObjectUtilManager::getBoardDescription()
{
QByteArray ret;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
if (!pm)
return 0;
UAVObjectManager *om = pm->getObject<UAVObjectManager>();
if (!om)
return 0;
FirmwareIAPObj::DataFields firmwareIapData = getFirmwareIap();
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(om->getObject(QString("FirmwareIAPObj")));
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
obj->requestUpdate();
loop.exec();
for (int i = 0; i < FirmwareIAPObj::DESCRIPTION_NUMELEM; i++)
ret.append(firmwareIapData.Description[i]);
UAVObjectField* descriptionField = obj->getField("Description");
// Description starts with an offset of
for (uint i = 0; i < descriptionField->getNumElements(); ++i) {
ret.append(descriptionField->getValue(i).toInt());
}
return ret;
}

View File

@ -43,6 +43,8 @@
#include <QQueue>
#include <QComboBox>
#include <QDateTime>
#include <firmwareiapobj.h>
class UAVOBJECTUTIL_EXPORT UAVObjectUtilManager: public QObject
{
Q_OBJECT
@ -69,6 +71,8 @@ public:
static bool descriptionToStructure(QByteArray desc,deviceDescriptorStruct * struc);
UAVObjectManager* getObjectManager();
void saveObjectToSD(UAVObject *obj);
protected:
FirmwareIAPObj::DataFields getFirmwareIap();
signals:
void saveCompleted(int objectID, bool status);

View File

@ -51,37 +51,37 @@ Rectangle {
WelcomePageButton {
baseIconName: "flightdata"
label: "Flight Data"
onClicked: welcomePlugin.openPage("Mode1")
onClicked: welcomePlugin.openPage("Flight data")
}
WelcomePageButton {
baseIconName: "config"
label: "Configuration"
onClicked: welcomePlugin.openPage("Mode2")
onClicked: welcomePlugin.openPage("Configuration")
}
WelcomePageButton {
baseIconName: "planner"
label: "Flight Planner"
onClicked: welcomePlugin.openPage("Mode3")
onClicked: welcomePlugin.openPage("Flight Planner")
}
WelcomePageButton {
baseIconName: "scopes"
label: "Scopes"
onClicked: welcomePlugin.openPage("Mode4")
onClicked: welcomePlugin.openPage("Scopes")
}
WelcomePageButton {
baseIconName: "hitl"
label: "HIL"
onClicked: welcomePlugin.openPage("Mode5")
label: "HITL"
onClicked: welcomePlugin.openPage("HITL")
}
WelcomePageButton {
baseIconName: "firmware"
label: "Firmware"
onClicked: welcomePlugin.openPage("Mode6")
onClicked: welcomePlugin.openPage("Firmware")
}
} //icons grid
} // images row

View File

@ -124,7 +124,7 @@ void WelcomeMode::openUrl(const QString &url)
void WelcomeMode::openPage(const QString &page)
{
Core::ModeManager::instance()->activateMode(page);
Core::ModeManager::instance()->activateModeByWorkspaceName(page);
}
} // namespace Welcome

View File

@ -30,10 +30,11 @@ CLEAN_FLIGHT := YES
endif
# Set up targets
FW_TARGETS := $(addprefix fw_, coptercontrol) $(addprefix fw_, revolution)
FW_TARGETS_TOOLS := $(addprefix fw_, coptercontrol)
BL_TARGETS := $(addprefix bl_, coptercontrol)
BU_TARGETS := $(addprefix bu_, coptercontrol)
ALL_BOARDS := coptercontrol pipxtreme revolution
FW_TARGETS := $(addprefix fw_, $(ALL_BOARDS))
FW_TARGETS_TOOLS := $(addprefix fw_, $(ALL_BOARDS))
BL_TARGETS := $(addprefix bl_, $(ALL_BOARDS))
BU_TARGETS := $(addprefix bu_, $(ALL_BOARDS))
help:
@echo

View File

@ -22,6 +22,7 @@ device=$(hdiutil attach "${TEMP_FILE}" | \
cp -r "${APP_PATH}" "/Volumes/${VOL_NAME}"
#cp -r "${FW_DIR}" "/Volumes/${VOL_NAME}/firmware"
cp "${FW_DIR}/fw_coptercontrol-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware"
cp "${FW_DIR}/fw_pipxtreme-${PACKAGE_LBL}.opfw" "/Volumes/${VOL_NAME}/Firmware"
cp "${BUILD_DIR}/uavobject-synthetics/matlab/OPLogConvert.m" "/Volumes/${VOL_NAME}/Utilities"

View File

@ -1,25 +1,6 @@
<xml>
<object name="ActuatorSettings" singleinstance="true" settings="true">
<description>Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType</description>
<field name="FixedWingRoll1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingRoll2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingPitch1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingPitch2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingYaw1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingYaw2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="FixedWingThrottle" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorN" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorNE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorSE" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorS" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorSW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="VTOLMotorNW" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="GroundVehicleThrottle1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="GroundVehicleThrottle2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="GroundVehicleSteering1" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="GroundVehicleSteering2" units="channel" type="enum" elements="1" options="Channel1,Channel2,Channel3,Channel4,Channel5,Channel6,Channel7,Channel8,Channel9,Channel10,None" defaultvalue="None"/>
<field name="ChannelUpdateFreq" units="Hz" type="uint16" elements="4" defaultvalue="50"/>
<field name="ChannelMax" units="us" type="int16" elements="10" defaultvalue="1000"/>
<field name="ChannelNeutral" units="us" type="int16" elements="10" defaultvalue="1000"/>

View File

@ -1,8 +1,8 @@
<xml>
<object name="GCSReceiver" singleinstance="true" settings="false">
<description>A receiver channel group carried over the telemetry link.</description>
<field name="Channel" units="us" type="uint16" elements="6"/>
<access gcs="readwrite" flight="readwrite"/>
<field name="Channel" units="us" type="uint16" elements="8"/>
<access gcs="readwrite" flight="readonly"/>
<telemetrygcs acked="false" updatemode="onchange" period="0"/>
<telemetryflight acked="false" updatemode="onchange" period="0"/>
<logging updatemode="manual" period="0"/>

View File

@ -18,9 +18,9 @@
<field name="Arming" units="" type="enum" elements="1" options="Always Disarmed,Always Armed,Roll Left,Roll Right,Pitch Forward,Pitch Aft,Yaw Left,Yaw Right" defaultvalue="Always Disarmed"/>
<!-- Note these options should be identical to those in StabilizationDesired.StabilizationMode -->
<field name="Stabilization1Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization2Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization3Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization1Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization2Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar" defaultvalue="Attitude,Attitude,Rate"/>
<field name="Stabilization3Settings" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar" defaultvalue="Attitude,Attitude,Rate"/>
<!-- Note these options values should be identical to those defined in FlightMode -->
<field name="FlightModePosition" units="" type="enum" elements="3" options="Manual,Stabilized1,Stabilized2,Stabilized3,AltitudeHold,VelocityControl,PositionHold,ReturnToBase,PathPlanner" defaultvalue="Manual,Stabilized1,Stabilized2"/>

View File

@ -1,7 +1,7 @@
<xml>
<object name="ObjectPersistence" singleinstance="true" settings="false">
<description>Someone who knows please enter this</description>
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,FullErase,Completed"/>
<field name="Operation" units="" type="enum" elements="1" options="NOP,Load,Save,Delete,FullErase,Completed,Error"/>
<field name="Selection" units="" type="enum" elements="1" options="SingleObject,AllSettings,AllMetaObjects,AllObjects"/>
<field name="ObjectID" units="" type="uint32" elements="1"/>
<field name="InstanceID" units="" type="uint32" elements="1"/>

View File

@ -14,6 +14,7 @@
<field name="Retries" units="" type="uint16" elements="1" defaultvalue="0"/>
<field name="Errors" units="" type="uint16" elements="1" defaultvalue="0"/>
<field name="UAVTalkErrors" units="" type="uint16" elements="1" defaultvalue="0"/>
<field name="Dropped" units="" type="uint16" elements="1" defaultvalue="0"/>
<field name="Resets" units="" type="uint16" elements="1" defaultvalue="0"/>
<field name="TXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>
<field name="RXRate" units="Bps" type="uint16" elements="1" defaultvalue="0"/>

View File

@ -6,7 +6,7 @@
<field name="Yaw" units="degrees" type="float" elements="1"/>
<field name="Throttle" units="%" type="float" elements="1"/>
<!-- These values should match those in ManualControlCommand.Stabilization{1,2,3}Settings -->
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling"/>
<field name="StabilizationMode" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="None,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="1000"/>

View File

@ -13,6 +13,15 @@
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,"/>
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,"/>
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,"/>
<field name="VbarSensitivity" units="frac" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0.5,0.5,0.5"/>
<field name="VbarRollPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
<field name="VbarPitchPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
<field name="VbarYawPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
<field name="VbarTau" units="sec" type="float" elements="1" defaultvalue="0.5"/>
<field name="VbarGyroSuppress" units="%" type="int8" elements="1" defaultvalue="30"/>
<field name="VbarPiroComp" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="VbarMaxAngle" units="deg" type="uint8" elements="1" defaultvalue="10"/>
<field name="GyroTau" units="" type="float" elements="1" defaultvalue="0.005"/>

View File

@ -2,7 +2,7 @@
<object name="SystemSettings" singleinstance="true" settings="true">
<description>Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand</description>
<field name="AirframeType" units="" type="enum" elements="1" options="FixedWing,FixedWingElevon,FixedWingVtail,VTOL,HeliCP,QuadX,QuadP,Hexa,Octo,Custom,HexaX,OctoV,OctoCoaxP,OctoCoaxX,HexaCoax,Tri,GroundVehicleCar,GroundVehicleDifferential,GroundVehicleMotorcycle" defaultvalue="FixedWing"/>
<field name="GUIConfigData" units="bits" type="uint32" elements="2" defaultvalue="0"/>
<field name="GUIConfigData" units="bits" type="uint32" elements="4" defaultvalue="0"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
<telemetryflight acked="true" updatemode="onchange" period="0"/>