HAL_SITL: removed the special code for cygwin

we no longer need special timing code for cygwin
This commit is contained in:
Andrew Tridgell 2015-04-28 13:15:40 +10:00
parent 063a33ebce
commit 42d2addbdd
1 changed files with 0 additions and 44 deletions

View File

@ -11,17 +11,6 @@
#include <signal.h>
#include <pthread.h>
#ifdef __CYGWIN__
#include <stdio.h>
#include <stdlib.h>
#include <assert.h>
#include <windows.h>
#include <string.h>
#include <memory.h>
#include <process.h>
#include <time.h>
#endif
using namespace AVR_SITL;
extern const AP_HAL::HAL& hal;
@ -41,11 +30,6 @@ bool SITLScheduler::_in_io_proc = false;
struct timeval SITLScheduler::_sketch_start_time;
#ifdef __CYGWIN__
double SITLScheduler::_cyg_freq = 0;
long SITLScheduler::_cyg_start = 0;
#endif
static void sigcont_handler(int)
{
}
@ -63,39 +47,16 @@ SITLScheduler::SITLScheduler(SITL_State *sitlState) :
void SITLScheduler::init(void *unused)
{
gettimeofday(&_sketch_start_time,NULL);
#ifdef __CYGWIN__
LARGE_INTEGER lFreq, lCnt;
QueryPerformanceFrequency(&lFreq);
_cyg_freq = (double)lFreq.LowPart;
QueryPerformanceCounter(&lCnt);
_cyg_start = lCnt.LowPart;
#endif
}
#ifdef __CYGWIN__
double SITLScheduler::_cyg_sec()
{
LARGE_INTEGER lCnt;
long tcnt;
QueryPerformanceCounter(&lCnt);
tcnt = lCnt.LowPart - _cyg_start;
return ((double)tcnt) / _cyg_freq;
}
#endif
uint64_t SITLScheduler::_micros64()
{
#ifdef __CYGWIN__
return (uint64_t)(_cyg_sec() * 1.0e6);
#else
struct timeval tp;
gettimeofday(&tp,NULL);
uint64_t ret = 1.0e6*((tp.tv_sec + (tp.tv_usec*1.0e-6)) -
(_sketch_start_time.tv_sec +
(_sketch_start_time.tv_usec*1.0e-6)));
return ret;
#endif
}
uint64_t SITLScheduler::micros64()
@ -116,17 +77,12 @@ uint64_t SITLScheduler::millis64()
if (stopped_clock_usec) {
return stopped_clock_usec/1000;
}
#ifdef __CYGWIN__
// 1000 ms in a second
return (uint64_t)(_cyg_sec() * 1000);
#else
struct timeval tp;
gettimeofday(&tp,NULL);
uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) -
(_sketch_start_time.tv_sec +
(_sketch_start_time.tv_usec*1.0e-6)));
return ret;
#endif
}
uint32_t SITLScheduler::millis()