AP_HAL_SITL: use millis/micros/panic functions

This commit is contained in:
Caio Marcelo de Oliveira Filho 2015-11-20 12:11:17 +09:00 committed by Randy Mackay
parent a76c9e0051
commit 85d12efbef
8 changed files with 22 additions and 22 deletions

View File

@ -177,8 +177,8 @@ void SITL_State::_fdm_input_step(void)
} }
// simulate RC input at 50Hz // simulate RC input at 50Hz
if (hal.scheduler->millis() - last_pwm_input >= 20 && _sitl->rc_fail == 0) { if (AP_HAL::millis() - last_pwm_input >= 20 && _sitl->rc_fail == 0) {
last_pwm_input = hal.scheduler->millis(); last_pwm_input = AP_HAL::millis();
new_rc_input = true; new_rc_input = true;
} }
@ -214,7 +214,7 @@ void SITL_State::_fdm_input_step(void)
void SITL_State::wait_clock(uint64_t wait_time_usec) void SITL_State::wait_clock(uint64_t wait_time_usec)
{ {
while (hal.scheduler->micros64() < wait_time_usec) { while (AP_HAL::micros64() < wait_time_usec) {
_fdm_input_step(); _fdm_input_step();
} }
} }
@ -270,10 +270,10 @@ void SITL_State::_fdm_input(void)
_update_count++; _update_count++;
count++; count++;
if (hal.scheduler->millis() - last_report > 1000) { if (AP_HAL::millis() - last_report > 1000) {
//fprintf(stdout, "SIM %u FPS\n", count); //fprintf(stdout, "SIM %u FPS\n", count);
count = 0; count = 0;
last_report = hal.scheduler->millis(); last_report = AP_HAL::millis();
} }
break; break;
@ -385,7 +385,7 @@ void SITL_State::_simulator_servos(Aircraft::sitl_input &input)
} }
// output at chosen framerate // output at chosen framerate
uint32_t now = hal.scheduler->micros(); uint32_t now = AP_HAL::micros();
float deltat = (now - last_update_usec) * 1.0e-6f; float deltat = (now - last_update_usec) * 1.0e-6f;
last_update_usec = now; last_update_usec = now;
@ -494,7 +494,7 @@ void SITL_State::_simulator_output(bool synthetic_clock_mode)
control.turbulance = _sitl->wind_turbulance * 100; control.turbulance = _sitl->wind_turbulance * 100;
// zero the wind for the first 15s to allow pitot calibration // zero the wind for the first 15s to allow pitot calibration
if (hal.scheduler->millis() < 15000) { if (AP_HAL::millis() < 15000) {
control.speed = 0; control.speed = 0;
} }

View File

@ -86,7 +86,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
float speedup = 1.0f; float speedup = 1.0f;
if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) { if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
hal.scheduler->panic("out of memory"); AP_HAL::panic("out of memory");
} }
signal(SIGFPE, _sig_fpe); signal(SIGFPE, _sig_fpe);

View File

@ -86,7 +86,7 @@ void SITLUARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
_tcp_start_connection(port, wait); _tcp_start_connection(port, wait);
} else if (strcmp(devtype, "tcpclient") == 0) { } else if (strcmp(devtype, "tcpclient") == 0) {
if (args2 == NULL) { if (args2 == NULL) {
hal.scheduler->panic("Invalid tcp client path: %s", path); AP_HAL::panic("Invalid tcp client path: %s", path);
} }
uint16_t port = atoi(args2); uint16_t port = atoi(args2);
_tcp_start_client(args1, port); _tcp_start_client(args1, port);
@ -95,7 +95,7 @@ void SITLUARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
::printf("UART connection %s:%u\n", args1, baudrate); ::printf("UART connection %s:%u\n", args1, baudrate);
_uart_start_connection(args1, baudrate); _uart_start_connection(args1, baudrate);
} else { } else {
hal.scheduler->panic("Invalid device path: %s", path); AP_HAL::panic("Invalid device path: %s", path);
} }
free(s); free(s);
} }
@ -363,7 +363,7 @@ void SITLUARTDriver::_uart_start_connection(const char *path, uint32_t baudrate)
} }
if (_fd == -1) { if (_fd == -1) {
hal.scheduler->panic("Unable to open UART %s", path); AP_HAL::panic("Unable to open UART %s", path);
} }
// set non-blocking // set non-blocking

View File

@ -44,7 +44,7 @@ void SITL_State::_update_barometer(float altitude)
} }
// 80Hz // 80Hz
uint32_t now = hal.scheduler->millis(); uint32_t now = AP_HAL::millis();
if ((now - last_update) < 12) { if ((now - last_update) < 12) {
return; return;
} }

View File

@ -48,7 +48,7 @@ void SITL_State::_update_compass(float rollDeg, float pitchDeg, float yawDeg)
Vector3f new_mag_data = _compass->getHIL(0) + noise + motor; Vector3f new_mag_data = _compass->getHIL(0) + noise + motor;
// 100Hz // 100Hz
uint32_t now = hal.scheduler->millis(); uint32_t now = AP_HAL::millis();
if ((now - last_update) < 10) { if ((now - last_update) < 10) {
return; return;
} }

View File

@ -75,7 +75,7 @@ int SITL_State::gps_pipe(void)
pipe(fd); pipe(fd);
gps_state.gps_fd = fd[1]; gps_state.gps_fd = fd[1];
gps_state.client_fd = fd[0]; gps_state.client_fd = fd[0];
gps_state.last_update = _scheduler->millis(); gps_state.last_update = AP_HAL::millis();
HALSITL::SITLUARTDriver::_set_nonblocking(gps_state.gps_fd); HALSITL::SITLUARTDriver::_set_nonblocking(gps_state.gps_fd);
HALSITL::SITLUARTDriver::_set_nonblocking(fd[0]); HALSITL::SITLUARTDriver::_set_nonblocking(fd[0]);
return gps_state.client_fd; return gps_state.client_fd;
@ -93,7 +93,7 @@ int SITL_State::gps2_pipe(void)
pipe(fd); pipe(fd);
gps2_state.gps_fd = fd[1]; gps2_state.gps_fd = fd[1];
gps2_state.client_fd = fd[0]; gps2_state.client_fd = fd[0];
gps2_state.last_update = _scheduler->millis(); gps2_state.last_update = AP_HAL::millis();
HALSITL::SITLUARTDriver::_set_nonblocking(gps2_state.gps_fd); HALSITL::SITLUARTDriver::_set_nonblocking(gps2_state.gps_fd);
HALSITL::SITLUARTDriver::_set_nonblocking(fd[0]); HALSITL::SITLUARTDriver::_set_nonblocking(fd[0]);
return gps2_state.client_fd; return gps2_state.client_fd;
@ -248,7 +248,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d)
status.differential_status = 0; status.differential_status = 0;
status.res = 0; status.res = 0;
status.time_to_first_fix = 0; status.time_to_first_fix = 0;
status.uptime = hal.scheduler->millis(); status.uptime = AP_HAL::millis();
velned.time = time_week_ms; velned.time = time_week_ms;
velned.ned_north = 100.0f * d->speedN; velned.ned_north = 100.0f * d->speedN;
@ -752,7 +752,7 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
} }
// run at configured GPS rate (default 5Hz) // run at configured GPS rate (default 5Hz)
if ((hal.scheduler->millis() - gps_state.last_update) < (uint32_t)(1000/_sitl->gps_hertz)) { if ((AP_HAL::millis() - gps_state.last_update) < (uint32_t)(1000/_sitl->gps_hertz)) {
return; return;
} }
@ -764,8 +764,8 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
read(gps2_state.gps_fd, &c, 1); read(gps2_state.gps_fd, &c, 1);
} }
gps_state.last_update = hal.scheduler->millis(); gps_state.last_update = AP_HAL::millis();
gps2_state.last_update = hal.scheduler->millis(); gps2_state.last_update = AP_HAL::millis();
d.latitude = latitude + glitch_offsets.x; d.latitude = latitude + glitch_offsets.x;
d.longitude = longitude + glitch_offsets.y; d.longitude = longitude + glitch_offsets.y;
@ -773,7 +773,7 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude,
if (_sitl->gps_drift_alt > 0) { if (_sitl->gps_drift_alt > 0) {
// slow altitude drift // slow altitude drift
d.altitude += _sitl->gps_drift_alt*sinf(hal.scheduler->millis()*0.001f*0.02f); d.altitude += _sitl->gps_drift_alt*sinf(AP_HAL::millis()*0.001f*0.02f);
} }
d.speedN = speedN; d.speedN = speedN;

View File

@ -43,7 +43,7 @@ uint16_t SITL_State::_airspeed_sensor(float airspeed)
return 0xFFFF; return 0xFFFF;
} }
// add delay // add delay
uint32_t now = hal.scheduler->millis(); uint32_t now = AP_HAL::millis();
uint32_t best_time_delta_wind = 200; // initialise large time representing buffer entry closest to current time - delay. uint32_t best_time_delta_wind = 200; // initialise large time representing buffer entry closest to current time - delay.
uint8_t best_index_wind = 0; // initialise number representing the index of the entry in buffer closest to delay. uint8_t best_index_wind = 0; // initialise number representing the index of the entry in buffer closest to delay.

View File

@ -42,7 +42,7 @@ void SITL_State::_update_flow(void)
} }
// update at the requested rate // update at the requested rate
uint32_t now = hal.scheduler->millis(); uint32_t now = AP_HAL::millis();
if (now - last_flow_ms < 1000*(1.0f/_sitl->flow_rate)) { if (now - last_flow_ms < 1000*(1.0f/_sitl->flow_rate)) {
return; return;
} }