int mpeg_instance_init(mpeg_struct_t *Mpeg_Struct, FileInfo_t *mpgfile) { #ifndef AVR32 timer_interval(&Mpeg_Struct->FrameDisplay, 1000/24); #endif mpgfile->Offset = 0; optind = 1; opterr = 0; optopt = '?'; Mpeg_Struct->framenum = 0; Mpeg_Struct->decoder = mpeg2_init (); if (Mpeg_Struct->decoder == NULL) { return 0; } Mpeg_Struct->info = mpeg2_info (Mpeg_Struct->decoder); Mpeg_Struct->size = (unsigned int)-1; Mpeg_Struct->temporal_reference =(unsigned int)-1; #ifdef Mpeg_Buffering RtcTimeCalDisplay(); _FatData_ReadSection(mpgfile, (unsigned char*)0x80000000 + 0x2000000, 0, 0x2000000); RtcTimeCalDisplay(); #endif return 1; }
bool srf02_start(SRF02_t *structure, SRF02_COMMANDS command) { if(structure->busy) return true; timer_interval(&structure->Timeout_Timer, 80); structure->busy = true; Twi_t* TwiStruct = structure->TWI; unsigned char dev_addr = 0x70; if(structure->addr) dev_addr = structure->addr; unsigned char tmp[2]; switch(command) { case SRF02_START_RANGING: case SRF02_FAKE_RANGING: tmp[0] = 0; tmp[1] = command + structure->measure_unit; if(twi.tx(TwiStruct, dev_addr, tmp, 2)) structure->reg_inst = command; break; default: return false; } return true; }
/************************************************************************** * Description: handles recurring task * Returns: none * Notes: none **************************************************************************/ void bacnet_task(void) { struct mstp_rx_packet pkt = {{0}}; bool pdu_available = false; /* hello, World! */ if (Device_ID != Device_Object_Instance_Number()) { Device_ID = Device_Object_Instance_Number(); Send_I_Am(&Handler_Transmit_Buffer[0]); } /* handle the timers */ if (timer_interval_expired(&DCC_Timer)) { timer_interval_reset(&DCC_Timer); dcc_timer_seconds(DCC_CYCLE_SECONDS); led_on_interval(LED_DEBUG,500); } if (timer_interval_expired(&TSM_Timer)) { timer_interval_reset(&TSM_Timer); tsm_timer_milliseconds(timer_interval(&TSM_Timer)); } reinit_task(); bacnet_test_task(); /* handle the messaging */ if ((!dlmstp_send_pdu_queue_full()) && (!Ringbuf_Empty(&Receive_Queue))) { Ringbuf_Pop(&Receive_Queue, (uint8_t *)&pkt); pdu_available = true; } if (pdu_available) { led_on_interval(LED_APDU,125); npdu_handler(&pkt.src, &pkt.buffer[0], pkt.length); } }
DXL_COMM_ERR dxl_ping(DXL_ACTUATOR_t *settings, unsigned char id, unsigned char* err) { char tx_buff[6]; tx_buff[0] = 0xFF; tx_buff[1] = 0xFF; tx_buff[2] = id; tx_buff[3] = 2; tx_buff[4] = DXL_PING; tx_buff[5] = 0x0; dxl_insert_checksum(tx_buff); gpio.out(settings->TxEnGpio, 1); uart.puts(settings->Uart, tx_buff, tx_buff[3] + 4); gpio.out(settings->TxEnGpio, 0); unsigned char rx_cnt = 0; signed short rx_char; char rx_buff[150]; memset(rx_buff, 0, 150); bool preamble_ok = false; DXL_COMM_ERR errors = DXL_COMM_RXTIMEOUT; timer(timeout_timer); timer_interval(&timeout_timer, settings->timeout); while(1) { timer_enable(&timeout_timer); while(1) { rx_char = uart.getc_no_blocking(settings->Uart); if(rx_char != (signed short)-1) { if(rx_char == 0xFF && preamble_ok == false && rx_cnt < 2) { rx_buff[rx_cnt] = rx_char; rx_cnt++; break; } if(rx_char != 0xFF && rx_cnt == 1 && preamble_ok == false) rx_cnt = 0; if(rx_char != 0xFF && rx_cnt == 2 && preamble_ok == false) preamble_ok = true; if(preamble_ok == true) break; } if(timer_tick(&timeout_timer)) { return errors; } } if(preamble_ok) { if(rx_cnt < 56) rx_buff[rx_cnt++] = rx_char; else errors = DXL_COMM_OVERFLOW; if(rx_buff[LENGTH] > 54) { errors = DXL_COMM_RXCORRUPT; } if(rx_cnt > 3) { if(rx_cnt - 3 >= rx_buff[3]) { if(dxl_verify_checksum(rx_buff)) { *err = rx_buff[4]; return DXL_COMM_SUCCESS; } else { errors = DXL_COMM_CHECKSUM; } } } } } }
//####################################################################################### bool _put_roll_string(tDisplay *pDisplay, graphic_strings_t *StringsStruct) { if(!StringsStruct->TimerInitialized) { StringsStruct->TimerInitialized = true; if(!StringsStruct->TimerScrollInterval) StringsStruct->TimerScrollInterval = 1000; timer_interval(&StringsStruct->TimerScroll, StringsStruct->TimerScrollInterval); } bool Return = true; tRectangle sClipRegion; sClipRegion = pDisplay->sClipRegion; pDisplay->sClipRegion = StringsStruct->sClipRegion; if(!StringsStruct->WordWrap && timer_tick(&StringsStruct->TimerScroll)) { if(StringsStruct->X_Location + StringsStruct->string_width_get_function(pDisplay, StringsStruct->pFont, StringsStruct->Str->text, -1) < pDisplay->sClipRegion.sXMin) { StringsStruct->X_Location = StringsStruct->sClipRegion.sXMin; Return = false; } if(Return) { pDisplay->lcd_func.put_rectangle(pDisplay, pDisplay->sClipRegion.sXMin, pDisplay->sClipRegion.sYMin, pDisplay->sClipRegion.sXMax, pDisplay->sClipRegion.sYMax, true, StringsStruct->Background_Color); print_string_properties properties; memset(&properties, 0, sizeof(print_string_properties)); properties.pDisplay = pDisplay; properties.pFont = StringsStruct->pFont; properties.pcString = str_clone(properties.pcString, StringsStruct->Str); //properties.pcString = StringsStruct->Str; properties.lLength = -1; properties.foreground_color = StringsStruct->Foreground_Color; properties.background_color = StringsStruct->Background_Color; properties.ulOpaque = StringsStruct->ulOpaque; properties.ulVisible = StringsStruct->ulVisible; properties.WordWrap = StringsStruct->WordWrap; properties.lX = StringsStruct->X_Location; properties.lY = StringsStruct->Y_Location; properties._SelStart = 0; properties._SelLen = 0; pDisplay->lcd_func.put_string(&properties); pDisplay->lcd_func.box_cache_clean(pDisplay, pDisplay->sClipRegion.sXMin, pDisplay->sClipRegion.sYMin, pDisplay->sClipRegion.sXMax, pDisplay->sClipRegion.sYMax); StringsStruct->X_Location--; } } //else //{ // put_rectangle(pDisplay, pDisplay->sClipRegion.sXMin, pDisplay->sClipRegion.sYMin, pDisplay->sClipRegion.sXMax, pDisplay->sClipRegion.sYMax, true, StringsStruct->Background_Color); // StringsStruct->print_function(pDisplay, StringsStruct->pFont, Text, -1, StringsStruct->Foreground_Color, StringsStruct->Background_Color, StringsStruct->ulOpaque, StringsStruct->ulVisible, StringsStruct->WordWrap, StringsStruct->X_Location, StringsStruct->Y_Location, 0, 0); // box_cache_clean(pDisplay, pDisplay->sClipRegion.sXMin, pDisplay->sClipRegion.sYMin, pDisplay->sClipRegion.sXMax, pDisplay->sClipRegion.sYMax); //} pDisplay->sClipRegion = sClipRegion; return Return; }
static void* trd_timer(void* p) { timer_init(); for(;;) { timer_update(); if(timer_interval() >= speeds[GAME->level]) { move_down(); timer_reset(); } usleep(50); } }
bool ms5611_adc_get_cmd_send(MS5611_t *structure, unsigned long *data, unsigned char osr) { timer_interval(&structure->Timeout_Timer, 15); Twi_t *TwiStruct = structure->TWI; TwiStruct->MasterSlaveAddr = MS5611_ADDR; TwiStruct->TxBuff[0] = MS5611_ADC_READ_CMD; while(!SetupI2CReception(TwiStruct, 1, 3)) { if(timer_tick(&structure->Timeout_Timer)) return false; } if(TwiStruct->RxBuff[0] == 0 && TwiStruct->RxBuff[1] == 0 && TwiStruct->RxBuff[2] == 0) return false; *data = (TwiStruct->RxBuff[0] << 16) + (TwiStruct->RxBuff[1] << 8) + TwiStruct->RxBuff[2]; return true; }
bool ak8975_get_mag(AK8975_t *structure, signed short *X_Axis, signed short *Y_Axis, signed short *Z_Axis) { if(!ak8975_start_measure(structure)) return false; timer(Timeout); timer_interval(&Timeout, 11); timer_enable(&Timeout); while(!ak8975_ready(structure)) { if(timer_tick(&Timeout)) return false; } if(!ak8975_read_data(structure, X_Axis, Y_Axis, Z_Axis)) return false; return true; }
bool ak8975_display_result(AK8975_t *structure) { signed short Xg = 0; signed short Yg = 0; signed short Zg = 0; if(!ak8975_start_measure(structure)) return false; timer(Timeout); timer_interval(&Timeout, 11); timer_enable(&Timeout); while(!ak8975_ready(structure)) { if(timer_tick(&Timeout)) return false; } if(!ak8975_read_data(structure, &Xg, &Yg, &Zg)) return false; uart.printf(DebugCom, "AK8975: Magnetometer: Xg = %d, Yg = %d, Zg = %d\n\r", Xg, Yg, Zg); return true; }
static DXL_COMM_ERR dxl_write(DXL_ACTUATOR_t *settings, unsigned char comand_type, unsigned char id, unsigned char reg, unsigned char* send_data, unsigned char write_nr, unsigned char *aditional_info, unsigned char *aditional_info_len, unsigned char *dxl_err) { if(write_nr > 50 || write_nr + reg > 50 || id == 255) return false; char *tx_buff = malloc(write_nr + 7); if(!tx_buff) return DXL_COMM_BUFF_ALLOC; tx_buff[0] = 0xFF; tx_buff[1] = 0xFF; tx_buff[2] = id; if(write_nr) { tx_buff[3] = write_nr + 3; tx_buff[4] = comand_type; tx_buff[5] = reg; memcpy(tx_buff + 6, send_data, write_nr); dxl_insert_checksum(tx_buff); gpio.out(settings->TxEnGpio, 1); uart.puts(settings->Uart, tx_buff, tx_buff[3] + 7); gpio.out(settings->TxEnGpio, 0); } else { tx_buff[3] = 2; tx_buff[4] = comand_type; dxl_insert_checksum(tx_buff); gpio.out(settings->TxEnGpio, 1); uart.puts(settings->Uart, tx_buff, 6); gpio.out(settings->TxEnGpio, 0); } free(tx_buff); unsigned char rx_cnt = 0; signed short rx_char = 0; char rx_buff[54]; memset(rx_buff, 0, 54); bool preamble_ok = false; DXL_COMM_ERR errors = DXL_COMM_RXTIMEOUT; timer(timeout_timer); timer_interval(&timeout_timer, settings->timeout); while(1) { timer_enable(&timeout_timer); while(1) { rx_char = uart.getc_no_blocking(settings->Uart); if(rx_char != (signed short)-1) { if(rx_char == 0xFF && preamble_ok == false && rx_cnt < 2) { rx_buff[rx_cnt] = rx_char; rx_cnt++; break; } if(rx_char != 0xFF && rx_cnt == 1 && preamble_ok == false) rx_cnt = 0; if(rx_char != 0xFF && rx_cnt == 2 && preamble_ok == false) preamble_ok = true; if(preamble_ok == true) break; } if(timer_tick(&timeout_timer)) { return errors; } } if(rx_cnt < 56) rx_buff[rx_cnt++] = rx_char; else errors = DXL_COMM_OVERFLOW; if(rx_cnt > 3 && rx_cnt != (unsigned char)-1) { if(rx_buff[LENGTH] > 52) errors = DXL_COMM_RXCORRUPT; if(rx_cnt - 4 == rx_buff[LENGTH]) { if(dxl_verify_checksum(rx_buff)) { if(rx_cnt - 6) memcpy(aditional_info, rx_buff + 5, rx_cnt - 6); *dxl_err = rx_buff[4]; *aditional_info_len = rx_cnt - 6; return DXL_COMM_SUCCESS; } else errors = DXL_COMM_CHECKSUM; } } } }
/* * settings = structure that contain the uart and TXEN gpio structure settings. * buff = data to be writen. * id = DXL actuator ID. * reg = pointed register from where begin to write the buff data. * write_nr = number of bytes to be read. */ DXL_COMM_ERR dxl_read(DXL_ACTUATOR_t *settings, unsigned char* buff, unsigned char id, unsigned char reg, unsigned char read_nr, unsigned char *dxl_err) { if(read_nr > 50 || read_nr + reg > 50 || id == 255) return false; char tx_buff[8]; tx_buff[0] = 0xFF; tx_buff[1] = 0xFF; tx_buff[2] = id; tx_buff[3] = 4; tx_buff[4] = DXL_READ_DATA; tx_buff[5] = reg; tx_buff[6] = read_nr; tx_buff[7] = 0x0; dxl_insert_checksum(tx_buff); gpio.out(settings->TxEnGpio, 1); uart.puts(settings->Uart, tx_buff, tx_buff[3] + 4); gpio.out(settings->TxEnGpio, 0); unsigned char rx_cnt = 0; signed short rx_char = 0; char rx_buff[56]; memset(rx_buff, 0, 56); bool preamble_ok = false; DXL_COMM_ERR errors = DXL_COMM_RXTIMEOUT; timer(timeout_timer); timer_interval(&timeout_timer, settings->timeout); while(1) { timer_enable(&timeout_timer); while(1) { rx_char = uart.getc_no_blocking(settings->Uart); if(rx_char != (signed short)-1) { if(rx_char == 0xFF && preamble_ok == false && rx_cnt < 2) { rx_buff[rx_cnt] = rx_char; rx_cnt++; break; } if(rx_char != 0xFF && rx_cnt == 1 && preamble_ok == false) rx_cnt = 0; if(rx_char != 0xFF && rx_cnt == 2 && preamble_ok == false) preamble_ok = true; if(preamble_ok == true) break; } if(timer_tick(&timeout_timer)) { return errors; } } if(preamble_ok) { if(rx_cnt < 56) rx_buff[rx_cnt++] = rx_char; else errors = DXL_COMM_OVERFLOW; if(rx_cnt > 3 && rx_cnt != (unsigned char)-1) { if(rx_buff[LENGTH] > 54) { errors = DXL_COMM_RXCORRUPT; } if(rx_cnt - 4 == rx_buff[LENGTH]) { //UARTPuts(DebugCom, rx_buff, rx_buff[LENGTH] + 4); if(dxl_verify_checksum(rx_buff)) { memcpy(buff, rx_buff + 5, read_nr); *dxl_err = rx_buff[4]; return DXL_COMM_SUCCESS; } else { errors = DXL_COMM_CHECKSUM; } } } } } }
/** * @brief Reads a block of data from the EEPROM. * @param pBuffer : pointer to the buffer that receives the data read from * the EEPROM. * @param ReadAddr : EEPROM's internal address to start reading from. * @param NumByteToRead : pointer to the variable holding number of bytes to * be read from the EEPROM. * * @note The variable pointed by NumByteToRead is reset to 0 when all the * data are read from the EEPROM. Application should monitor this * variable in order know when the transfer is complete. * * @note When number of data to be read is higher than 1, this function just * configures the communication and enable the DMA channel to transfer data. * Meanwhile, the user application may perform other tasks. * When number of data to be read is 1, then the DMA is not used. The byte * is read in polling mode. * * @retval sEE_OK (0) if operation is correctly performed, else return value * different from sEE_OK (0) or the timeout user callback. */ uint32_t TWI_MasterWriteRead(new_twi* TwiStruct, unsigned int TransmitBytes, unsigned int ReceiveBytes) { uint32_t sEETimeout; /* Set the pointer to the Number of data to be read. This pointer will be used by the DMA Transfer Completer interrupt Handler in order to reset the variable to 0. User should check on this variable in order to know if the DMA transfer has been complete or not. */ uint16_t NumByteToRead = ReceiveBytes; I2C_TypeDef *I2Cx = sEE_I2C[TwiStruct->TwiNr]; /* If bus is freeze we will reset the unit and restore the settings. */ if(I2C_GetFlagStatus(sEE_I2C[TwiStruct->TwiNr], I2C_FLAG_AF | I2C_FLAG_ARLO) || (I2Cx->CR1 & (1 << 8))) { /* sEE_I2C Peripheral Enable */ I2C_TypeDef I2CxBack; I2CxBack.CR1 = I2Cx->CR1; I2CxBack.CR2 = I2Cx->CR2; I2CxBack.OAR1 = I2Cx->OAR1; I2CxBack.OAR2 = I2Cx->OAR2; I2CxBack.CCR = I2Cx->CCR; I2CxBack.TRISE = I2Cx->TRISE; I2C_SoftwareResetCmd(sEE_I2C[TwiStruct->TwiNr], ENABLE); I2C_SoftwareResetCmd(sEE_I2C[TwiStruct->TwiNr], DISABLE); I2Cx->TRISE = I2CxBack.TRISE; I2Cx->CCR = I2CxBack.CCR; I2Cx->OAR2 = I2CxBack.OAR2; I2Cx->OAR1 = I2CxBack.OAR1; I2Cx->CR2 = I2CxBack.CR2; I2Cx->CR1 = I2CxBack.CR1; } /*!< While the bus is busy */ timer(TimerBusyTimeout); timer_interval(&TimerBusyTimeout, TwiStruct->BusyTimeOut); timer_enable(&TimerBusyTimeout); while(I2C_GetFlagStatus(sEE_I2C[TwiStruct->TwiNr], I2C_FLAG_BUSY)) { if(timer_tick(&TimerBusyTimeout)) { I2C_TypeDef I2CxBack; I2CxBack.CR1 = I2Cx->CR1; I2CxBack.CR2 = I2Cx->CR2; I2CxBack.OAR1 = I2Cx->OAR1; I2CxBack.OAR2 = I2Cx->OAR2; I2CxBack.CCR = I2Cx->CCR; I2CxBack.TRISE = I2Cx->TRISE; I2C_SoftwareResetCmd(sEE_I2C[TwiStruct->TwiNr], ENABLE); I2C_SoftwareResetCmd(sEE_I2C[TwiStruct->TwiNr], DISABLE); I2Cx->TRISE = I2CxBack.TRISE; I2Cx->CCR = I2CxBack.CCR; I2Cx->OAR2 = I2CxBack.OAR2; I2Cx->OAR1 = I2CxBack.OAR1; I2Cx->CR2 = I2CxBack.CR2; I2Cx->CR1 = I2CxBack.CR1; break; } } unsigned int cnt = 0; if(!TwiStruct->NoSendWriteOnRead) { /*!< Send START condition */ I2C_GenerateSTART(sEE_I2C[TwiStruct->TwiNr], ENABLE); /*!< Test on EV5 and clear it (cleared by reading SR1 then writing to DR) */ sEETimeout = sEE_FLAG_TIMEOUT; while(!I2C_CheckEvent(sEE_I2C[TwiStruct->TwiNr], I2C_EVENT_MASTER_MODE_SELECT)) { if((sEETimeout--) == 0) { return false; } } /*!< Send EEPROM address for write */ I2C_Send7bitAddress(sEE_I2C[TwiStruct->TwiNr], TwiStruct->MasterSlaveAddr << 1, I2C_Direction_Transmitter); /*!< Test on EV6 and clear it */ sEETimeout = sEE_FLAG_TIMEOUT; while(!I2C_CheckEvent(sEE_I2C[TwiStruct->TwiNr], I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED)) { if((sEETimeout--) == 0) { return false; } } for(; cnt < TransmitBytes; cnt++) { /*!< Send the EEPROM's internal address to read from: MSB of the address first */ I2C_SendData(sEE_I2C[TwiStruct->TwiNr], TwiStruct->TxBuff[cnt]); /*!< Test on EV8 and clear it */ sEETimeout = sEE_FLAG_TIMEOUT; while(!I2C_CheckEvent(sEE_I2C[TwiStruct->TwiNr], I2C_EVENT_MASTER_BYTE_TRANSMITTED)) { if((sEETimeout--) == 0) { return false; } } } } if(ReceiveBytes) { /* If number of data to be read is 1, then DMA couldn't be used */ /* One Byte Master Reception procedure (POLLING) ---------------------------*/ if (NumByteToRead < 2) { /*!< Send STRAT condition a second time */ I2C_GenerateSTART(sEE_I2C[TwiStruct->TwiNr], ENABLE); /*!< Test on EV5 and clear it (cleared by reading SR1 then writing to DR) */ sEETimeout = sEE_FLAG_TIMEOUT; while(!I2C_CheckEvent(sEE_I2C[TwiStruct->TwiNr], I2C_EVENT_MASTER_MODE_SELECT)) { if((sEETimeout--) == 0) { return false; } } /*!< Send EEPROM address for read */ I2C_Send7bitAddress(sEE_I2C[TwiStruct->TwiNr], TwiStruct->MasterSlaveAddr << 1, I2C_Direction_Receiver); /* Wait on ADDR flag to be set (ADDR is still not cleared at this level */ sEETimeout = sEE_FLAG_TIMEOUT; while(I2C_GetFlagStatus(sEE_I2C[TwiStruct->TwiNr], I2C_FLAG_ADDR) == RESET) { if((sEETimeout--) == 0) { return false; } } /*!< Disable Acknowledgement */ I2C_AcknowledgeConfig(sEE_I2C[TwiStruct->TwiNr], DISABLE); /* Call User callback for critical section start (should typically disable interrupts) */ sEE_EnterCriticalSection_UserCallback(); /* Clear ADDR register by reading SR1 then SR2 register (SR1 has already been read) */ (void)sEE_I2C[TwiStruct->TwiNr]->SR2; /*!< Send STOP Condition */ I2C_GenerateSTOP(sEE_I2C[TwiStruct->TwiNr], ENABLE); /* Call User callback for critical section end (should typically re-enable interrupts) */ sEE_ExitCriticalSection_UserCallback(); /* Wait for the byte to be received */ sEETimeout = sEE_FLAG_TIMEOUT; while(I2C_GetFlagStatus(sEE_I2C[TwiStruct->TwiNr], I2C_FLAG_RXNE) == RESET) { if((sEETimeout--) == 0) { return false; } } /*!< Read the byte received from the EEPROM */ *TwiStruct->RxBuff = I2C_ReceiveData(sEE_I2C[TwiStruct->TwiNr]); /*!< Decrement the read bytes counter */ NumByteToRead--; /* Wait to make sure that STOP control bit has been cleared */ sEETimeout = sEE_FLAG_TIMEOUT; while(sEE_I2C[TwiStruct->TwiNr]->CR1 & I2C_CR1_STOP) { if((sEETimeout--) == 0) { return false; } } /*!< Re-Enable Acknowledgement to be ready for another reception */ I2C_AcknowledgeConfig(sEE_I2C[TwiStruct->TwiNr], ENABLE); } else/* More than one Byte Master Reception procedure (DMA) -----------------*/ { /*!< Send STRAT condition a second time */ I2C_GenerateSTART(sEE_I2C[TwiStruct->TwiNr], ENABLE); /*!< Test on EV5 and clear it (cleared by reading SR1 then writing to DR) */ sEETimeout = sEE_FLAG_TIMEOUT; while(!I2C_CheckEvent(sEE_I2C[TwiStruct->TwiNr], I2C_EVENT_MASTER_MODE_SELECT)) { if((sEETimeout--) == 0) { return false; } } /*!< Send EEPROM address for read */ I2C_Send7bitAddress(sEE_I2C[TwiStruct->TwiNr], TwiStruct->MasterSlaveAddr << 1, I2C_Direction_Receiver); /* If number of data to be read is 1, then DMA couldn't be used */ /* One Byte Master Reception procedure (POLLING) ---------------------------*/ //if (NumByteToRead < 2) //{ /* Wait on ADDR flag to be set (ADDR is still not cleared at this level */ sEETimeout = sEE_FLAG_TIMEOUT; while(I2C_GetFlagStatus(sEE_I2C[TwiStruct->TwiNr], I2C_FLAG_ADDR) == RESET) { if((sEETimeout--) == 0) { return false; } } (void)sEE_I2C[TwiStruct->TwiNr]->SR2; cnt = 0; for(; cnt < ReceiveBytes; cnt++) { if(cnt == ReceiveBytes - 1) { /*!< Disable Acknowledgement */ I2C_AcknowledgeConfig(sEE_I2C[TwiStruct->TwiNr], DISABLE); /* Call User callback for critical section start (should typically disable interrupts) */ sEE_EnterCriticalSection_UserCallback(); /* Clear ADDR register by reading SR1 then SR2 register (SR1 has already been read) */ (void)sEE_I2C[TwiStruct->TwiNr]->SR2; /*!< Send STOP Condition */ I2C_GenerateSTOP(sEE_I2C[TwiStruct->TwiNr], ENABLE); /* Call User callback for critical section end (should typically re-enable interrupts) */ sEE_ExitCriticalSection_UserCallback(); } /* Wait for the byte to be received */ sEETimeout = sEE_FLAG_TIMEOUT; while(I2C_GetFlagStatus(sEE_I2C[TwiStruct->TwiNr], I2C_FLAG_RXNE) == RESET) { if((sEETimeout--) == 0) { return false; } } /*!< Read the byte received from the EEPROM */ TwiStruct->RxBuff[cnt] = I2C_ReceiveData(sEE_I2C[TwiStruct->TwiNr]); } /* Wait to make sure that STOP control bit has been cleared */ sEETimeout = sEE_FLAG_TIMEOUT; while(sEE_I2C[TwiStruct->TwiNr]->CR1 & I2C_CR1_STOP) { if((sEETimeout--) == 0) { return false; } } /*!< Re-Enable Acknowledgement to be ready for another reception */ I2C_AcknowledgeConfig(sEE_I2C[TwiStruct->TwiNr], ENABLE); } } else { /* Call User callback for critical section start (should typically disable interrupts) */ sEE_EnterCriticalSection_UserCallback(); /* Clear ADDR register by reading SR1 then SR2 register (SR1 has already been read) */ (void)sEE_I2C[TwiStruct->TwiNr]->SR2; /*!< Send STOP Condition */ I2C_GenerateSTOP(sEE_I2C[TwiStruct->TwiNr], ENABLE); /* Call User callback for critical section end (should typically re-enable interrupts) */ sEE_ExitCriticalSection_UserCallback(); /* Wait for the byte to be received */ sEETimeout = sEE_FLAG_TIMEOUT; while(I2C_GetFlagStatus(sEE_I2C[TwiStruct->TwiNr], I2C_FLAG_RXNE) == RESET) { if((sEETimeout--) == 0) { return true; } } } /* If all operations OK, return sEE_OK (0) */ return true; }
bool sht11_write(SHT11_t *structure, unsigned char cmd, unsigned char *status_reg) { /* * If flag busy is true, signify that a command has been already send * and now we will wait to read data. * If flag busy is true will return true, to return signal that the command is send * and now we will wait for response. */ if(structure->busy) return true; /* * This is the single case that this function run forward. * This will go on only if a is called for first time, response is read * nack is received or timeout is occurred. * Now will set the timeout in millisecond and send the command. */ timer_interval(&structure->Timeout_Timer, 500); structure->busy = true; gpio_function_set(structure->Scl, GPIO_OUT_OPEN_DRAIN); gpio_function_set(structure->Sda, GPIO_OUT_OPEN_DRAIN); /* Send transmission start. * ___ ___ * data = \_____/ * ___ ___ * clk = _/ \_/ \__ */ gpio_out(structure->Scl, 0); sht11_delay(structure); gpio_out(structure->Scl, 1); sht11_delay(structure); gpio_out(structure->Sda, 0); sht11_delay(structure); gpio_out(structure->Scl, 0); sht11_delay(structure); gpio_out(structure->Scl, 1); sht11_delay(structure); gpio_out(structure->Sda, 1); sht11_delay(structure); gpio_out(structure->Scl, 0); sht11_delay(structure); /* * Send command. */ unsigned char data_cnt = 0; unsigned char _cmd = cmd; for(; data_cnt < 8; data_cnt++) { if(_cmd & 0x80) gpio_out(structure->Sda, 1); else gpio_out(structure->Sda, 0); sht11_delay(structure); gpio_out(structure->Scl, 1); sht11_delay(structure); gpio_out(structure->Scl, 0); if(data_cnt == 7) { gpio_out(structure->Sda, 1); gpio_function_set(structure->Sda, GPIO_IN_PULL_UP); } sht11_delay(structure); _cmd = _cmd << 1; } gpio_out(structure->Scl, 1); sht11_delay(structure); signed int ack = gpio_in(structure->Sda); gpio_out(structure->Scl, 0); sht11_delay(structure); if(ack) { structure->busy = false; return false; } structure->reg_inst = cmd; if(cmd == SHT11_WRITE_STATUS_REG) { /* * Write status register */ gpio_function_set(structure->Sda, GPIO_OUT_OPEN_DRAIN); unsigned char st_reg = *status_reg; for(data_cnt = 0; data_cnt < 8; data_cnt++) { if(st_reg & 0x80) gpio_out(structure->Sda, 1); else gpio_out(structure->Sda, 0); sht11_delay(structure); gpio_out(structure->Scl, 1); sht11_delay(structure); gpio_out(structure->Scl, 0); if(data_cnt == 7) { gpio_out(structure->Sda, 1); gpio_function_set(structure->Sda, GPIO_IN_PULL_UP); } sht11_delay(structure); st_reg = st_reg << 1; } gpio_out(structure->Scl, 1); sht11_delay(structure); signed int ack = gpio_in(structure->Sda); gpio_out(structure->Scl, 0); sht11_delay(structure); if(ack) { structure->busy = false; return false; } structure->busy = false; } else if(cmd == SHT11_READ_STATUS_REG) { /* * Read status register. */ unsigned char st_reg = 0; for(data_cnt = 0; data_cnt < 8; data_cnt++) { st_reg = st_reg << 1; gpio_out(structure->Scl, 1); sht11_delay(structure); if(gpio_in(structure->Sda)) st_reg |= 1; gpio_out(structure->Scl, 0); if(data_cnt == 7) { gpio_function_set(structure->Sda, GPIO_OUT_OPEN_DRAIN); gpio_out(structure->Sda, 0); } sht11_delay(structure); } gpio_out(structure->Scl, 1); sht11_delay(structure); gpio_out(structure->Scl, 0); gpio_function_set(structure->Sda, GPIO_IN_PULL_UP); sht11_delay(structure); *status_reg = st_reg; /* * Read checksum. */ unsigned char chk = 0; for(data_cnt = 0; data_cnt < 8; data_cnt++) { chk = chk << 1; gpio_out(structure->Scl, 1); sht11_delay(structure); if(gpio_in(structure->Sda)) chk |= 1; gpio_out(structure->Scl, 0); sht11_delay(structure); } gpio_out(structure->Scl, 1); sht11_delay(structure); gpio_out(structure->Scl, 0); sht11_delay(structure); structure->busy = false; } return true; }
int main(void) { board_init(); /*******************************************************/ //lan_interface_init(); //httpd_init(); timer(TimerReadSensors); timer_interval(&TimerReadSensors, 1000); timer(TimerBlinkLed); timer_interval(&TimerBlinkLed, 1000); //mpu60x0_9150_init(MPU60x0); //mhc5883_init(MHC5883); bool Led1Status = false; unsigned char sht11_status_reg = 0; bool sht11_read_mode = false; while(1) { //lwip_idle(); if(sht11_read_mode) { /* * Send start temperature measure * The sht11_write function will send the command if internal flag 'busy' is false and return true. * If flag busy is true will return true. */ if(sht11_write(SHT11, SHT11_START_MEASURE_TEMPERATURE, &sht11_status_reg)) { /* * Pool SGT11 and read data if is ready * If read is complete will return true, else will return false. * When read is complete the busy flag will be set to false, this will allow * sht11_write to send another command if is called. */ if(sht11_read(SHT11)) /* * Read complete. * Now you can send another command. */ sht11_read_mode = false; } } else { /* * Send start humidity measure * The sht11_write function will send the command if internal flag 'busy' is false and return true. * If flag busy is true will return true. */ if(sht11_write(SHT11, SHT11_START_MEASURE_HUMIDITY, &sht11_status_reg)) { /* * Pool SGT11 and read data if is ready * If read is complete will return true, else will return false. * When read is complete the busy flag will be set to false, this will allow * sht11_write to send another command if is called. */ if(sht11_read(SHT11)) /* * Read complete. * Now you can send another command. */ sht11_read_mode = true; } } /* Send start ranging */ if(srf02_start(SRF02, SRF02_START_RANGING)) /* * Pool SRF02 and read data if is ready * If data is not ready, this function will not freeze, * If data ready will return true, if not wil return false. */ srf02_read(SRF02); if(timer_tick(&TimerBlinkLed)) { if(Led1Status) { gpio_out(LED[0], 0); gpio_out(LED[1], 0); gpio_out(LED[2], 0); gpio_out(LED[3], 0); timer_interval(&TimerBlinkLed, 100); timer_enable(&TimerBlinkLed); Led1Status = false; } else { gpio_out(LED[0], 1); gpio_out(LED[1], 1); gpio_out(LED[2], 1); gpio_out(LED[3], 1); timer_interval(&TimerBlinkLed, 900); timer_enable(&TimerBlinkLed); Led1Status = true; } } if(0/*timer_tick(&TimerReadSensors)*/) { Time_Update(); ms5611_display_pressure_result(MS5611, MS5611_CONVERT_OSR_1024); mpu60x0_9150_temperature_display_result(MPU60x0); mpu60x0_9150_giroscope_display_result(MPU60x0); mpu60x0_9150_accelerometer_display_result(MPU60x0); mhc5883_display_result(MHC5883); sht11_display_data(SHT11); srf02_display_data(SRF02); UARTprintf(DebugCom, "ADC1:\n\rCH0 = %d, CH1 = %d, TempSensor = %2.2f\n\r\n\r", ADC[0]->ConvResult[0], ADC[0]->ConvResult[1], (float)(((float)1775 - (float)ADC[0]->ConvResult[2]) / 5.337) + (float)25); /* * Send to each DXL the position and speed. */ DXL_SYNK_IND_PACKET_t DXL_PACK[18]; #define MOT1 270 DXL_PACK[0].id = 1; DXL_PACK[0].data[0] = (unsigned char)((unsigned short)MOT1);// Goal position DXL_PACK[0].data[1] = (unsigned char)((unsigned short)MOT1 >> 8); DXL_PACK[0].data[2] = 0;// Speed DXL_PACK[0].data[3] = 2; #define MOT2 736 DXL_PACK[1].id = 2; DXL_PACK[1].data[0] = (unsigned char)((unsigned short)MOT2);// Goal position DXL_PACK[1].data[1] = (unsigned char)((unsigned short)MOT2 >> 8); DXL_PACK[1].data[2] = 0;// Speed DXL_PACK[1].data[3] = 2; #define MOT3 376 DXL_PACK[2].id = 3; DXL_PACK[2].data[0] = (unsigned char)((unsigned short)MOT3);// Goal position DXL_PACK[2].data[1] = (unsigned char)((unsigned short)MOT3 >> 8); DXL_PACK[2].data[2] = 0;// Speed DXL_PACK[2].data[3] = 2; #define MOT4 662 DXL_PACK[3].id = 4; DXL_PACK[3].data[0] = (unsigned char)((unsigned short)MOT4);// Goal position DXL_PACK[3].data[1] = (unsigned char)((unsigned short)MOT4 >> 8); DXL_PACK[3].data[2] = 0;// Speed DXL_PACK[3].data[3] = 2; #define MOT5 300 DXL_PACK[4].id = 5; DXL_PACK[4].data[0] = (unsigned char)((unsigned short)MOT5);// Goal position DXL_PACK[4].data[1] = (unsigned char)((unsigned short)MOT5 >> 8); DXL_PACK[4].data[2] = 0;// Speed DXL_PACK[4].data[3] = 2; #define MOT6 726 DXL_PACK[5].id = 6; DXL_PACK[5].data[0] = (unsigned char)((unsigned short)MOT6);// Goal position DXL_PACK[5].data[1] = (unsigned char)((unsigned short)MOT6 >> 8); DXL_PACK[5].data[2] = 0;// Speed DXL_PACK[5].data[3] = 2; #define MOT7 376 DXL_PACK[6].id = 7; DXL_PACK[6].data[0] = (unsigned char)((unsigned short)MOT7);// Goal position DXL_PACK[6].data[1] = (unsigned char)((unsigned short)MOT7 >> 8); DXL_PACK[6].data[2] = 0;// Speed DXL_PACK[6].data[3] = 2; #define MOT8 660 DXL_PACK[7].id = 8; DXL_PACK[7].data[0] = (unsigned char)((unsigned short)MOT8);// Goal position DXL_PACK[7].data[1] = (unsigned char)((unsigned short)MOT8 >> 8); DXL_PACK[7].data[2] = 0;// Speed DXL_PACK[7].data[3] = 2; #define MOT9 512 DXL_PACK[8].id = 9; DXL_PACK[8].data[0] = (unsigned char)((unsigned short)MOT9);// Goal position DXL_PACK[8].data[1] = (unsigned char)((unsigned short)MOT9 >> 8); DXL_PACK[8].data[2] = 0;// Speed DXL_PACK[8].data[3] = 2; #define MOT10 512 DXL_PACK[9].id = 10; DXL_PACK[9].data[0] = (unsigned char)((unsigned short)MOT10);// Goal position DXL_PACK[9].data[1] = (unsigned char)((unsigned short)MOT10 >> 8); DXL_PACK[9].data[2] = 0;// Speed DXL_PACK[9].data[3] = 2; #define MOT11 512 DXL_PACK[10].id = 11; DXL_PACK[10].data[0] = (unsigned char)((unsigned short)MOT11);// Goal position DXL_PACK[10].data[1] = (unsigned char)((unsigned short)MOT11 >> 8); DXL_PACK[10].data[2] = 0;// Speed DXL_PACK[10].data[3] = 2; #define MOT12 512 DXL_PACK[11].id = 12; DXL_PACK[11].data[0] = (unsigned char)((unsigned short)MOT12);// Goal position DXL_PACK[11].data[1] = (unsigned char)((unsigned short)MOT12 >> 8); DXL_PACK[11].data[2] = 0;// Speed DXL_PACK[11].data[3] = 2; #define MOT13 512 DXL_PACK[12].id = 13; DXL_PACK[12].data[0] = (unsigned char)((unsigned short)MOT13);// Goal position DXL_PACK[12].data[1] = (unsigned char)((unsigned short)MOT13 >> 8); DXL_PACK[12].data[2] = 0;// Speed DXL_PACK[12].data[3] = 2; #define MOT14 512 DXL_PACK[13].id = 14; DXL_PACK[13].data[0] = (unsigned char)((unsigned short)MOT13);// Goal position DXL_PACK[13].data[1] = (unsigned char)((unsigned short)MOT14 >> 8); DXL_PACK[13].data[2] = 0;// Speed DXL_PACK[13].data[3] = 2; #define MOT15 512 DXL_PACK[14].id = 15; DXL_PACK[14].data[0] = (unsigned char)((unsigned short)MOT15);// Goal position DXL_PACK[14].data[1] = (unsigned char)((unsigned short)MOT15 >> 8); DXL_PACK[14].data[2] = 0;// Speed DXL_PACK[14].data[3] = 2; #define MOT16 512 DXL_PACK[15].id = 16; DXL_PACK[15].data[0] = (unsigned char)((unsigned short)MOT16);// Goal position DXL_PACK[15].data[1] = (unsigned char)((unsigned short)MOT16 >> 8); DXL_PACK[15].data[2] = 0;// Speed DXL_PACK[15].data[3] = 2; #define MOT17 512 DXL_PACK[16].id = 17; DXL_PACK[16].data[0] = (unsigned char)((unsigned short)MOT17);// Goal position DXL_PACK[16].data[1] = (unsigned char)((unsigned short)MOT17 >> 8); DXL_PACK[16].data[2] = 0;// Speed DXL_PACK[16].data[3] = 2; #define MOT18 512 DXL_PACK[17].id = 18; DXL_PACK[17].data[0] = (unsigned char)((unsigned short)MOT18);// Goal position DXL_PACK[17].data[1] = (unsigned char)((unsigned short)MOT18 >> 8); DXL_PACK[17].data[2] = 0;// Speed DXL_PACK[17].data[3] = 2; /* * Send synk write to all 18 DXL's position and speed. */ dxl_synk_write(DXL, DXL_GOAL_POSITION_L, DXL_PACK, 4, 18); } }
void TouchCalibrate(LcdTouch_t* structure, tDisplay *pDisplay) { timer_interval(&TimerTouchCalibrate, 25); put_rectangle(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y, true, ClrBlack); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); double TouchX = 0, TouchY = 0; double screen_max_x = structure->screen_max_x; double screen_max_y = structure->screen_max_y; structure->screen_max_x = 4095; structure->screen_max_y = 4095; structure->LcdTouch_L_Calibration_Value = 0; structure->LcdTouch_R_Calibration_Value = 4095; structure->LcdTouch_U_Calibration_Value = 0; structure->LcdTouch_D_Calibration_Value = 4095; double LcdTouch_L_Calibration_Value; double LcdTouch_R_Calibration_Value; double LcdTouch_U_Calibration_Value; double LcdTouch_D_Calibration_Value; TouchPaintPoint(pDisplay, (((double)pDisplay->raster_timings->X * (double)12.5) / (double)100), (((double)pDisplay->raster_timings->Y * (double)12.5) / (double)100), ClrRed); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); double Xbuffer[FilterTouchCalibrateSize]; double Ybuffer[FilterTouchCalibrateSize]; unsigned int Cnt = 0; unsigned int Cnt1 = 0; while(1) { if(timer_tick(&TimerTouchCalibrate)) { TouchIdle(structure); if(Cnt < FilterTouchCalibrateSize && structure->TouchResponse.touch_event1 == Cursor_Move) { Xbuffer[Cnt] = structure->TouchResponse.x1; Ybuffer[Cnt] = structure->TouchResponse.y1; Cnt++; } else if(structure->TouchResponse.touch_event1 == Cursor_Up) { for(Cnt1 = 1; Cnt1 < Cnt; Cnt1++) { Xbuffer[0] += Xbuffer[Cnt1]; Ybuffer[0] += Ybuffer[Cnt1]; } Xbuffer[0] /= Cnt; Ybuffer[0] /= Cnt; TouchX = Xbuffer[0]; TouchY = Ybuffer[0]; break; } } } //TouchX = structure->TouchResponse.x1; //TouchY = structure->TouchResponse.y1; LcdTouch_L_Calibration_Value = (double)TouchX; LcdTouch_U_Calibration_Value = (double)TouchY; put_rectangle(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y, true, ClrBlack); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); //delay(500); TouchPaintPoint(pDisplay, (double)pDisplay->raster_timings->X - (((double)pDisplay->raster_timings->X * (double)12.5) / (double)100), (((double)pDisplay->raster_timings->Y * (double)12.5) / (double)100), ClrRed); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); Cnt = 0; Cnt1 = 0; while(1) { if(timer_tick(&TimerTouchCalibrate)) { TouchIdle(structure); if(Cnt < FilterTouchCalibrateSize && structure->TouchResponse.touch_event1 == Cursor_Move) { Xbuffer[Cnt] = structure->TouchResponse.x1; Ybuffer[Cnt] = structure->TouchResponse.y1; Cnt++; } else if(structure->TouchResponse.touch_event1 == Cursor_Up) { for(Cnt1 = 1; Cnt1 < Cnt; Cnt1++) { Xbuffer[0] += Xbuffer[Cnt1]; Ybuffer[0] += Ybuffer[Cnt1]; } Xbuffer[0] /= Cnt; Ybuffer[0] /= Cnt; TouchX = Xbuffer[0]; TouchY = Ybuffer[0]; break; } } } //TouchX = structure->TouchResponse.x1; //TouchY = structure->TouchResponse.y1; LcdTouch_R_Calibration_Value = (double)TouchX; LcdTouch_U_Calibration_Value += (double)TouchY; put_rectangle(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y, true, ClrBlack); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); //delay(500); TouchPaintPoint(pDisplay, (double)pDisplay->raster_timings->X - (((double)pDisplay->raster_timings->X * (double)12.5) / (double)100), (double)pDisplay->raster_timings->Y - (((double)pDisplay->raster_timings->Y * (double)12.5) / (double)100), ClrRed); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); Cnt = 0; Cnt1 = 0; while(1) { if(timer_tick(&TimerTouchCalibrate)) { TouchIdle(structure); if(Cnt < FilterTouchCalibrateSize && structure->TouchResponse.touch_event1 == Cursor_Move) { Xbuffer[Cnt] = structure->TouchResponse.x1; Ybuffer[Cnt] = structure->TouchResponse.y1; Cnt++; } else if(structure->TouchResponse.touch_event1 == Cursor_Up) { for(Cnt1 = 1; Cnt1 < Cnt; Cnt1++) { Xbuffer[0] += Xbuffer[Cnt1]; Ybuffer[0] += Ybuffer[Cnt1]; } Xbuffer[0] /= Cnt; Ybuffer[0] /= Cnt; TouchX = Xbuffer[0]; TouchY = Ybuffer[0]; break; } } } //TouchX = structure->TouchResponse.x1; //TouchY = structure->TouchResponse.y1; LcdTouch_R_Calibration_Value += (double)TouchX; LcdTouch_D_Calibration_Value = (double)TouchY; put_rectangle(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y, true, ClrBlack); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); //delay(500); TouchPaintPoint(pDisplay, (((double)pDisplay->raster_timings->X * (double)12.5) / (double)100), (double)pDisplay->raster_timings->Y - (((double)pDisplay->raster_timings->Y * (double)12.5) / (double)100), ClrRed); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); Cnt = 0; Cnt1 = 0; while(1) { if(timer_tick(&TimerTouchCalibrate)) { TouchIdle(structure); if(Cnt < FilterTouchCalibrateSize && structure->TouchResponse.touch_event1 == Cursor_Move) { Xbuffer[Cnt] = structure->TouchResponse.x1; Ybuffer[Cnt] = structure->TouchResponse.y1; Cnt++; } else if(structure->TouchResponse.touch_event1 == Cursor_Up) { for(Cnt1 = 1; Cnt1 < Cnt; Cnt1++) { Xbuffer[0] += Xbuffer[Cnt1]; Ybuffer[0] += Ybuffer[Cnt1]; } Xbuffer[0] /= Cnt; Ybuffer[0] /= Cnt; TouchX = Xbuffer[0]; TouchY = Ybuffer[0]; break; } } } //TouchX = structure->TouchResponse.x1; //TouchY = structure->TouchResponse.y1; LcdTouch_L_Calibration_Value += (double)TouchX; LcdTouch_D_Calibration_Value += (double)TouchY; put_rectangle(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y, true, ClrBlack); box_cache_clean(pDisplay, 0, 0, pDisplay->raster_timings->X, pDisplay->raster_timings->Y); //CacheDataCleanBuff((unsigned int)&pDisplay->DisplayData + 32, pDisplay->Width * pDisplay->Height * 4); LcdTouch_L_Calibration_Value /= 2; LcdTouch_R_Calibration_Value /= 2; LcdTouch_U_Calibration_Value /= 2; LcdTouch_D_Calibration_Value /= 2; double X_middle = LcdTouch_L_Calibration_Value + ((LcdTouch_R_Calibration_Value - LcdTouch_L_Calibration_Value) / 2); LcdTouch_L_Calibration_Value = X_middle - ((X_middle - LcdTouch_L_Calibration_Value) * 1.33); LcdTouch_R_Calibration_Value = X_middle + ((LcdTouch_R_Calibration_Value - X_middle) * 1.33); double Y_middle = LcdTouch_U_Calibration_Value + ((LcdTouch_D_Calibration_Value - LcdTouch_U_Calibration_Value) / 2); LcdTouch_U_Calibration_Value = Y_middle - ((Y_middle - LcdTouch_U_Calibration_Value) * 1.33); LcdTouch_D_Calibration_Value = Y_middle + ((LcdTouch_D_Calibration_Value - Y_middle) * 1.33); structure->screen_max_x = screen_max_x; structure->screen_max_y = screen_max_y; structure->LcdTouch_L_Calibration_Value = LcdTouch_L_Calibration_Value; structure->LcdTouch_R_Calibration_Value = LcdTouch_R_Calibration_Value; structure->LcdTouch_U_Calibration_Value = LcdTouch_U_Calibration_Value; structure->LcdTouch_D_Calibration_Value = LcdTouch_D_Calibration_Value; }
int main(void) { board_init(); timer(TimerReadSensors); timer_interval(&TimerReadSensors, 1000); timer(TimerBlinkLed); timer_interval(&TimerBlinkLed, 1000); /*ms5611_prom_data ms5611_prom_data; ms5611_init(&ms5611_prom_data, TWI[0]); mpu60x0_init(TWI[0], 0); mhc5883_init(TWI[0]);*/ bool Led1Status = false; while(1) { if(timer_tick(&TimerBlinkLed)) { if(Led1Status) { gpio_out(LED1, 0); timer_interval(&TimerBlinkLed, 100); timer_enable(&TimerBlinkLed); Led1Status = false; } else { gpio_out(LED1, 1); timer_interval(&TimerBlinkLed, 900); timer_enable(&TimerBlinkLed); Led1Status = true; } } if(timer_tick(&TimerReadSensors)) { DXL_DATA_t buffer[18]; memset(&buffer, 0, sizeof(buffer)); unsigned char dxl_err[18]; memset(&dxl_err, 0, sizeof(dxl_err)); DXL_COMM_ERR err_ret[18]; memset(&err_ret, 0, sizeof(err_ret)); unsigned char dxl_cnt; for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) err_ret[dxl_cnt] = dxl_read(DXL, (unsigned char *)&buffer[dxl_cnt] , dxl_cnt + 1 , 0, sizeof(buffer[0]), &dxl_err[dxl_cnt]); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL data: ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(dxl_cnt + 1); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL com status = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(err_ret[dxl_cnt]); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL err = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(dxl_err[dxl_cnt]); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL model nr = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].model_number); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL version = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].version); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL ID = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].id); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL baud rate = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].baud_rate); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL return delay time = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].return_delay_time); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL cw angle limit = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].cw_angle_limit); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL ccw angle limit = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].ccw_angle_limit); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL limit temperature = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].limit_temperature); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL down limit voltage = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].down_limit_voltage); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL up limit voltage = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].up_limit_voltage); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL mdxl torque limit = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].mdxl_torque); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL status return level = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].status_return_level); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL alarm led = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].alarm_led); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL alarm shutdown = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].alarm_shutdown); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL down calibration = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].down_calibration); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL up calibration = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].up_calibration); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL torque enable = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].torque_enable); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL led = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].led); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL cw compliance margin = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].cw_compliance_margin); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL ccw compliance margin = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].ccw_compliance_margin); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL cw compliance slope = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].cw_compliance_slope); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL ccw compliance slope = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].ccw_compliance_slope); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL goal position = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].goal_position); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL moving speed = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].moving_speed); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL torque limit = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].torque_limit); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL present position = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].present_position); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL present speed = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].present_speed); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL present load = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].present_load); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL present voltage = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].present_voltage); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL present temperature = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].present_temperature); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL registered instruction= ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].registered_instruction); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL moving = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].moving); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL lock = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].lock); UARTPuts(DebugCom, "\n\r", -1); UARTPuts(DebugCom, "DXL punch = ", -1); for(dxl_cnt = 0; dxl_cnt < sizeof(dxl_id_table); dxl_cnt++) display_value(buffer[dxl_cnt].punch); UARTPuts(DebugCom, "\n\r\n\r", -1); /* * Send to each DXL the position and speed. */ DXL_SYNK_IND_PACKET_t DXL_PACK[18]; #define MOT1 270 DXL_PACK[0].id = 1; DXL_PACK[0].data[0] = (unsigned char)((unsigned short)MOT1);// Goal position DXL_PACK[0].data[1] = (unsigned char)((unsigned short)MOT1 >> 8); DXL_PACK[0].data[2] = 0;// Speed DXL_PACK[0].data[3] = 2; #define MOT2 736 DXL_PACK[1].id = 2; DXL_PACK[1].data[0] = (unsigned char)((unsigned short)MOT2);// Goal position DXL_PACK[1].data[1] = (unsigned char)((unsigned short)MOT2 >> 8); DXL_PACK[1].data[2] = 0;// Speed DXL_PACK[1].data[3] = 2; #define MOT3 376 DXL_PACK[2].id = 3; DXL_PACK[2].data[0] = (unsigned char)((unsigned short)MOT3);// Goal position DXL_PACK[2].data[1] = (unsigned char)((unsigned short)MOT3 >> 8); DXL_PACK[2].data[2] = 0;// Speed DXL_PACK[2].data[3] = 2; #define MOT4 662 DXL_PACK[3].id = 4; DXL_PACK[3].data[0] = (unsigned char)((unsigned short)MOT4);// Goal position DXL_PACK[3].data[1] = (unsigned char)((unsigned short)MOT4 >> 8); DXL_PACK[3].data[2] = 0;// Speed DXL_PACK[3].data[3] = 2; #define MOT5 300 DXL_PACK[4].id = 5; DXL_PACK[4].data[0] = (unsigned char)((unsigned short)MOT5);// Goal position DXL_PACK[4].data[1] = (unsigned char)((unsigned short)MOT5 >> 8); DXL_PACK[4].data[2] = 0;// Speed DXL_PACK[4].data[3] = 2; #define MOT6 726 DXL_PACK[5].id = 6; DXL_PACK[5].data[0] = (unsigned char)((unsigned short)MOT6);// Goal position DXL_PACK[5].data[1] = (unsigned char)((unsigned short)MOT6 >> 8); DXL_PACK[5].data[2] = 0;// Speed DXL_PACK[5].data[3] = 2; #define MOT7 376 DXL_PACK[6].id = 7; DXL_PACK[6].data[0] = (unsigned char)((unsigned short)MOT7);// Goal position DXL_PACK[6].data[1] = (unsigned char)((unsigned short)MOT7 >> 8); DXL_PACK[6].data[2] = 0;// Speed DXL_PACK[6].data[3] = 2; #define MOT8 660 DXL_PACK[7].id = 8; DXL_PACK[7].data[0] = (unsigned char)((unsigned short)MOT8);// Goal position DXL_PACK[7].data[1] = (unsigned char)((unsigned short)MOT8 >> 8); DXL_PACK[7].data[2] = 0;// Speed DXL_PACK[7].data[3] = 2; #define MOT9 512 DXL_PACK[8].id = 9; DXL_PACK[8].data[0] = (unsigned char)((unsigned short)MOT9);// Goal position DXL_PACK[8].data[1] = (unsigned char)((unsigned short)MOT9 >> 8); DXL_PACK[8].data[2] = 0;// Speed DXL_PACK[8].data[3] = 2; #define MOT10 512 DXL_PACK[9].id = 10; DXL_PACK[9].data[0] = (unsigned char)((unsigned short)MOT10);// Goal position DXL_PACK[9].data[1] = (unsigned char)((unsigned short)MOT10 >> 8); DXL_PACK[9].data[2] = 0;// Speed DXL_PACK[9].data[3] = 2; #define MOT11 512 DXL_PACK[10].id = 11; DXL_PACK[10].data[0] = (unsigned char)((unsigned short)MOT11);// Goal position DXL_PACK[10].data[1] = (unsigned char)((unsigned short)MOT11 >> 8); DXL_PACK[10].data[2] = 0;// Speed DXL_PACK[10].data[3] = 2; #define MOT12 512 DXL_PACK[11].id = 12; DXL_PACK[11].data[0] = (unsigned char)((unsigned short)MOT12);// Goal position DXL_PACK[11].data[1] = (unsigned char)((unsigned short)MOT12 >> 8); DXL_PACK[11].data[2] = 0;// Speed DXL_PACK[11].data[3] = 2; #define MOT13 512 DXL_PACK[12].id = 13; DXL_PACK[12].data[0] = (unsigned char)((unsigned short)MOT13);// Goal position DXL_PACK[12].data[1] = (unsigned char)((unsigned short)MOT13 >> 8); DXL_PACK[12].data[2] = 0;// Speed DXL_PACK[12].data[3] = 2; #define MOT14 512 DXL_PACK[13].id = 14; DXL_PACK[13].data[0] = (unsigned char)((unsigned short)MOT13);// Goal position DXL_PACK[13].data[1] = (unsigned char)((unsigned short)MOT14 >> 8); DXL_PACK[13].data[2] = 0;// Speed DXL_PACK[13].data[3] = 2; #define MOT15 512 DXL_PACK[14].id = 15; DXL_PACK[14].data[0] = (unsigned char)((unsigned short)MOT15);// Goal position DXL_PACK[14].data[1] = (unsigned char)((unsigned short)MOT15 >> 8); DXL_PACK[14].data[2] = 0;// Speed DXL_PACK[14].data[3] = 2; #define MOT16 512 DXL_PACK[15].id = 16; DXL_PACK[15].data[0] = (unsigned char)((unsigned short)MOT16);// Goal position DXL_PACK[15].data[1] = (unsigned char)((unsigned short)MOT16 >> 8); DXL_PACK[15].data[2] = 0;// Speed DXL_PACK[15].data[3] = 2; #define MOT17 512 DXL_PACK[16].id = 17; DXL_PACK[16].data[0] = (unsigned char)((unsigned short)MOT17);// Goal position DXL_PACK[16].data[1] = (unsigned char)((unsigned short)MOT17 >> 8); DXL_PACK[16].data[2] = 0;// Speed DXL_PACK[16].data[3] = 2; #define MOT18 512 DXL_PACK[17].id = 18; DXL_PACK[17].data[0] = (unsigned char)((unsigned short)MOT18);// Goal position DXL_PACK[17].data[1] = (unsigned char)((unsigned short)MOT18 >> 8); DXL_PACK[17].data[2] = 0;// Speed DXL_PACK[17].data[3] = 2; /* * Send synk write to all 18 DXL's position and speed. */ dxl_synk_write(DXL, DXL_GOAL_POSITION_L, DXL_PACK, 4, 18); /* * Send position and speed for each DXL without synk. */ /*unsigned char aditional_info[48]; unsigned char aditional_info_len; dxl_write_data(DXL, 1, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[0].data, 4, aditional_info, &aditional_info_len, &dxl_err[0]); dxl_write_data(DXL, 2, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[1].data, 4, aditional_info, &aditional_info_len, &dxl_err[1]); dxl_write_data(DXL, 3, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[2].data, 4, aditional_info, &aditional_info_len, &dxl_err[2]); dxl_write_data(DXL, 4, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[3].data, 4, aditional_info, &aditional_info_len, &dxl_err[3]); dxl_write_data(DXL, 5, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[4].data, 4, aditional_info, &aditional_info_len, &dxl_err[4]); dxl_write_data(DXL, 6, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[5].data, 4, aditional_info, &aditional_info_len, &dxl_err[5]); dxl_write_data(DXL, 7, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[6].data, 4, aditional_info, &aditional_info_len, &dxl_err[6]); dxl_write_data(DXL, 8, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[7].data, 4, aditional_info, &aditional_info_len, &dxl_err[7]); dxl_write_data(DXL, 9, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[8].data, 4, aditional_info, &aditional_info_len, &dxl_err[8]); dxl_write_data(DXL, 10, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[9].data, 4, aditional_info, &aditional_info_len, &dxl_err[9]); dxl_write_data(DXL, 11, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[10].data, 4, aditional_info, &aditional_info_len, &dxl_err[10]); dxl_write_data(DXL, 12, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[11].data, 4, aditional_info, &aditional_info_len, &dxl_err[11]); dxl_write_data(DXL, 13, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[12].data, 4, aditional_info, &aditional_info_len, &dxl_err[12]); dxl_write_data(DXL, 14, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[13].data, 4, aditional_info, &aditional_info_len, &dxl_err[13]); dxl_write_data(DXL, 15, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[14].data, 4, aditional_info, &aditional_info_len, &dxl_err[14]); dxl_write_data(DXL, 16, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[15].data, 4, aditional_info, &aditional_info_len, &dxl_err[15]); dxl_write_data(DXL, 17, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[16].data, 4, aditional_info, &aditional_info_len, &dxl_err[16]); dxl_write_data(DXL, 18, DXL_GOAL_POSITION_L, (unsigned char *)&DXL_PACK[17].data, 4, aditional_info, &aditional_info_len, &dxl_err[17]);*/ } }
/*#####################################################*/ int main(void) { board_init(); /*******************************************************/ timer_interval(&TimerScanTouch, 10); /*******************************************************/ #ifdef lcd #ifdef USE_BACK_SCREEN BackScreen = new_(new_screen); memcpy((void *)BackScreen, (void *)ScreenBuff, sizeof(new_screen)); #ifdef gcc BackScreen->DisplayData = malloc((BackScreen->raster_timings->X * BackScreen->raster_timings->Y * sizeof(BackScreen->DisplayData[0])) + (BackScreen->raster_timings->palete_len * sizeof(BackScreen->DisplayData[0]))); #else BackScreen->DisplayData = memalign(sizeof(BackScreen->DisplayData[0]) << 3, (BackScreen->raster_timings->X * BackScreen->raster_timings->Y * sizeof(BackScreen->DisplayData[0])) + (BackScreen->raster_timings->palete_len * sizeof(BackScreen->DisplayData[0]))); #endif MainWindow = new_window(NULL, BackScreen); #else MainWindow = new_window(NULL, ScreenBuff); #endif window_new_button(MainWindow, Btn1); window_new_checkbox(MainWindow, CB1); window_new_listbox(MainWindow, ListBox1); window_new_progressbar(MainWindow, PBar1); window_new_scrollbar(MainWindow, ScrollBar1); window_new_textbox(MainWindow, TextBox1); window_new_picturebox(MainWindow, PictureBox1); window_new_window(MainWindow, Window1); MainWindow->WindowMoveLimits.sXMin = 0; MainWindow->WindowMoveLimits.sXMax = ScreenBuff->raster_timings->X; MainWindow->WindowMoveLimits.sYMin = 20; MainWindow->WindowMoveLimits.sYMax = ScreenBuff->raster_timings->Y - 100; #ifdef USE_BACK_SCREEN KbdWindow = new_window(NULL, BackScreen); window_new_keyboard(KbdWindow, Kbd); HeaderWindow = new_window(NULL, BackScreen); #else KbdWindow = new_window(NULL, ScreenBuff); window_new_keyboard(KbdWindow, Kbd); HeaderWindow = new_window(NULL, ScreenBuff); #endif HeaderWindow->WindowMoveLimits.sXMin = 0; HeaderWindow->WindowMoveLimits.sXMax = ScreenBuff->raster_timings->X; HeaderWindow->WindowMoveLimits.sYMin = 0; HeaderWindow->WindowMoveLimits.sYMax = 20; HeaderWindow->HideHeader = true; HeaderWindow->HideHScroll = true; HeaderWindow->HideVScroll = true; KbdWindow->WindowMoveLimits.sXMin = 0; KbdWindow->WindowMoveLimits.sXMax = ScreenBuff->raster_timings->X; KbdWindow->WindowMoveLimits.sYMin = ScreenBuff->raster_timings->Y - 100; KbdWindow->WindowMoveLimits.sYMax = ScreenBuff->raster_timings->Y; KbdWindow->HideHeader = true; KbdWindow->HideHScroll = true; KbdWindow->HideVScroll = true; KbdWindow->Caption.Font = (tFont *)&g_sFontCmss18b; /* Set location and size of virtual keyboard */ Kbd->Position.X = 0; Kbd->Position.Y = 0; Kbd->Size.X = ScreenBuff->raster_timings->X - 6; Kbd->Size.Y = 98; Window1->Internals.FullScreen = false; Window1->Position.X = 400; Window1->Position.Y = 400; Window1->Size.X = 400; Window1->Size.Y = 300; window_new_button(Window1, Btn2); window_new_window(Window1, Window2); Window2->Internals.FullScreen = false; Window2->Position.X = 10; Window2->Position.Y = 50; Window2->Size.X = 300; Window2->Size.Y = 200; window_new_button(Window2, Btn3); window_new_tab_group(Window2, TabGroup1); //TabGroup1->Internals.FullScreen = false; TabGroup1->Position.X = 10; TabGroup1->Position.Y = 50; TabGroup1->Size.X = 200; TabGroup1->Size.Y = 100; tab_group_new_tab(TabGroup1, "Tab1"); tab_group_new_tab(TabGroup1, "Tab2"); tab_group_new_tab(TabGroup1, "Tab3"); tab_group_new_tab(TabGroup1, "Tab4"); tab_group_new_tab(TabGroup1, "Tab5"); tab_group_new_tab(TabGroup1, "Tab6"); tab_group_new_tab(TabGroup1, "Tab7"); tab_group_new_tab(TabGroup1, "Tab8"); tab_group_new_button(TabGroup1, Btn4, 0); tab_group_new_button(TabGroup1, Btn5, 1); tab_group_new_button(TabGroup1, Btn6, 2); tab_group_new_button(TabGroup1, Btn7, 3); tab_group_new_button(TabGroup1, Btn8, 4); tab_group_new_button(TabGroup1, Btn9, 5); tab_group_new_button(TabGroup1, Btn10, 6); tab_group_new_button(TabGroup1, Btn11, 7); Btn5->Position.X = 30; /* Enable clear background on refresh */ PictureBox1->PaintBackground = true; /* Set callback's for picture box*/ PictureBox1->Events.OnMove.CallBack = picture_box_callback; PictureBox1->Events.OnDown.CallBack = picture_box_callback_on_down; /* Refresh is used to refresh the picture box when the window or picture box position , size is modified */ PictureBox1->Events.Refresh.CallBack = picture_box_refresh_callback; /* Set callback's for Btn1*/ Btn1->Events.OnUp.CallbackData = PictureBox1; Btn1->Events.OnUp.CallBack = picture_box_clear_callback; /* Clear the picture box */ picture_box_clear_callback(PictureBox1); char TmpStr[30]; unsigned int CntItems = 0; for(CntItems = 0; CntItems < 100; CntItems++) { sprintf(TmpStr, "%d", CntItems); listbox_item_add(ListBox1, TmpStr); } listbox_item_insert(ListBox1, "Inserted Item", 1); listbox_item_remove(ListBox1, 3); string(TextBoxString, "Multiplatform SDK to create standalone applications\n\r1\n\r2\n\r3\n\r4\n\r5\n\r6\n\r7\n\r8\n\r9\n\r10\n\r11\n\r12\n\r13\n\r14\n\r15\n\r16\n\r17\n\r18"); TextBox1->text(TextBox1, TextBoxString); TextBox1->text(TextBox1, TextBox1->to_uper(TextBox1)); tControlCommandData control_comand; control_comand.Comand = Control_Nop; control_comand.CursorCoordonateUsed = true; #endif /*******************************************************/ /*arg's for console*/ char *argv[2]; argv[0] = NULL; /*******************************************************/ bool old_connected = false; #ifdef BridgeUsbDev0ToMmcSd0 if(sdCtrl[0].connected == false) usb_msc_dev_media_change_state(0, false); #elif defined(BridgeUsbDev0ToMmcSd1) if(sdCtrl[1].connected == false) usb_msc_dev_media_change_state(0, false); #endif /*******************************************************/ unsigned int PwrLoadCount = 0; /*******************************************************/ while(1) { if(timer_tick(&TimerScanTouch)) { if(PwrLoadCount) PwrLoadCount--; //UARTprintf(DebugCom, "X= %d, Y= %d, But= %d, Whel= %d.\n\r" , MouseXPosition, MouseYPosition, g_ulButtons, MouseWheel); #ifdef lcd #ifdef USE_BACK_SCREEN if(BackScreen) #else if(ScreenBuff) #endif { memset(&control_comand, 0, sizeof(tControlCommandData)); #ifdef touch if(TouchScreen->TouchScreen_Type == TouchScreen_Type_Int) TouchIdle(TouchScreen); else if(TouchScreen->TouchScreen_Type == TouchScreen_Type_FT5x06) ft5x06_TouchIdle(TouchScreen); control_comand.X = TouchScreen->TouchResponse.x1; control_comand.Y = TouchScreen->TouchResponse.y1; control_comand.Cursor = (CursorState)TouchScreen->TouchResponse.touch_event1; #endif #ifdef usb_1_mouse usb_mouse_host_idle(1, &control_comand); #elif defined(usb_1_msc) usb_msc_host_idle(1); #endif HeaderWindow->idle(HeaderWindow, &control_comand); MainWindow->idle(MainWindow, &control_comand); KbdWindow->idle(KbdWindow, &control_comand); #ifdef USE_BACK_SCREEN if(control_comand.WindowRefresh) ScreenReRefreshCnt = 2; if(ScreenReRefreshCnt) { ScreenReRefreshCnt--; screen_copy(ScreenBuff, BackScreen, true, control_comand.X, control_comand.Y, 0x00000000); //put_rectangle(ScreenBuff, control_comand.X, control_comand.Y, 2, 2, true, 0x00000000); //box_cache_clean(ScreenBuff, control_comand.X, control_comand.Y, 2, 2); } #else put_rectangle(ScreenBuff, control_comand.X, control_comand.Y, 2, 2, true, 0x00000000); box_cache_clean(ScreenBuff, control_comand.X, control_comand.Y, 2, 2); #endif } else PwrLoadCount++; #endif #ifdef BridgeUsbDev0ToMmcSd0 mmcsd_idle(&sdCtrl[0]); if(old_connected == false && sdCtrl[0].connected == true) { old_connected = true; usb_msc_dev_media_change_state(0, true); } else if(old_connected == true && sdCtrl[0].connected == false) { old_connected = false; usb_msc_dev_media_change_state(0, false); } #elif defined(BridgeUsbDev0ToMmcSd1) mmcsd_idle(&sdCtrl[1]); if(old_connected == false && sdCtrl[1].connected == true) { old_connected = true; usb_msc_dev_media_change_state(1, true); } else if(old_connected == true && sdCtrl[1].connected == false) { old_connected = false; usb_msc_dev_media_change_state(1, false); } #endif } signed int R_Chr = UARTGetcNoBlocking(DebugCom); argv[1] = (char *)R_Chr; console(2, argv); } }