mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
SITL: use millis/micros/panic functions
This commit is contained in:
parent
e839892524
commit
d343bfdc6c
@ -50,7 +50,7 @@ Gimbal::Gimbal(const struct sitl_fdm &_fdm) :
|
|||||||
void Gimbal::update(void)
|
void Gimbal::update(void)
|
||||||
{
|
{
|
||||||
// calculate delta time in seconds
|
// calculate delta time in seconds
|
||||||
uint32_t now_us = hal.scheduler->micros();
|
uint32_t now_us = AP_HAL::micros();
|
||||||
|
|
||||||
float delta_t = (now_us - last_update_us) * 1.0e-6f;
|
float delta_t = (now_us - last_update_us) * 1.0e-6f;
|
||||||
last_update_us = now_us;
|
last_update_us = now_us;
|
||||||
@ -230,7 +230,7 @@ void Gimbal::send_report(void)
|
|||||||
if (!seen_heartbeat) {
|
if (!seen_heartbeat) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint32_t now = hal.scheduler->millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
mavlink_message_t msg;
|
mavlink_message_t msg;
|
||||||
uint16_t len;
|
uint16_t len;
|
||||||
|
|
||||||
@ -262,7 +262,7 @@ void Gimbal::send_report(void)
|
|||||||
/*
|
/*
|
||||||
send a GIMBAL_REPORT message
|
send a GIMBAL_REPORT message
|
||||||
*/
|
*/
|
||||||
uint32_t now_us = hal.scheduler->micros();
|
uint32_t now_us = AP_HAL::micros();
|
||||||
if (now_us - last_report_us > reporting_period_ms*1000UL) {
|
if (now_us - last_report_us > reporting_period_ms*1000UL) {
|
||||||
mavlink_gimbal_report_t gimbal_report;
|
mavlink_gimbal_report_t gimbal_report;
|
||||||
float delta_time = (now_us - last_report_us) * 1.0e-6f;
|
float delta_time = (now_us - last_report_us) * 1.0e-6f;
|
||||||
|
@ -80,7 +80,7 @@ bool JSBSim::create_templates(void)
|
|||||||
|
|
||||||
FILE *f = fopen(jsbsim_script, "w");
|
FILE *f = fopen(jsbsim_script, "w");
|
||||||
if (f == NULL) {
|
if (f == NULL) {
|
||||||
hal.scheduler->panic("Unable to create jsbsim script %s", jsbsim_script);
|
AP_HAL::panic("Unable to create jsbsim script %s", jsbsim_script);
|
||||||
}
|
}
|
||||||
fprintf(f,
|
fprintf(f,
|
||||||
"<?xml version=\"1.0\" encoding=\"utf-8\"?>\n"
|
"<?xml version=\"1.0\" encoding=\"utf-8\"?>\n"
|
||||||
@ -125,7 +125,7 @@ bool JSBSim::create_templates(void)
|
|||||||
|
|
||||||
f = fopen(jsbsim_fgout, "w");
|
f = fopen(jsbsim_fgout, "w");
|
||||||
if (f == NULL) {
|
if (f == NULL) {
|
||||||
hal.scheduler->panic("Unable to create jsbsim fgout script %s", jsbsim_fgout);
|
AP_HAL::panic("Unable to create jsbsim fgout script %s", jsbsim_fgout);
|
||||||
}
|
}
|
||||||
fprintf(f, "<?xml version=\"1.0\"?>\n"
|
fprintf(f, "<?xml version=\"1.0\"?>\n"
|
||||||
"<output name=\"127.0.0.1\" type=\"FLIGHTGEAR\" port=\"%u\" protocol=\"udp\" rate=\"1000\"/>\n",
|
"<output name=\"127.0.0.1\" type=\"FLIGHTGEAR\" port=\"%u\" protocol=\"udp\" rate=\"1000\"/>\n",
|
||||||
@ -136,7 +136,7 @@ bool JSBSim::create_templates(void)
|
|||||||
asprintf(&jsbsim_reset, "%s/aircraft/%s/reset.xml", autotest_dir, jsbsim_model);
|
asprintf(&jsbsim_reset, "%s/aircraft/%s/reset.xml", autotest_dir, jsbsim_model);
|
||||||
f = fopen(jsbsim_reset, "w");
|
f = fopen(jsbsim_reset, "w");
|
||||||
if (f == NULL) {
|
if (f == NULL) {
|
||||||
hal.scheduler->panic("Unable to create jsbsim reset script %s", jsbsim_reset);
|
AP_HAL::panic("Unable to create jsbsim reset script %s", jsbsim_reset);
|
||||||
}
|
}
|
||||||
float r, p, y;
|
float r, p, y;
|
||||||
dcm.to_euler(&r, &p, &y);
|
dcm.to_euler(&r, &p, &y);
|
||||||
@ -177,7 +177,7 @@ bool JSBSim::start_JSBSim(void)
|
|||||||
int p[2];
|
int p[2];
|
||||||
int devnull = open("/dev/null", O_RDWR);
|
int devnull = open("/dev/null", O_RDWR);
|
||||||
if (pipe(p) != 0) {
|
if (pipe(p) != 0) {
|
||||||
hal.scheduler->panic("Unable to create pipe");
|
AP_HAL::panic("Unable to create pipe");
|
||||||
}
|
}
|
||||||
pid_t child_pid = fork();
|
pid_t child_pid = fork();
|
||||||
if (child_pid == 0) {
|
if (child_pid == 0) {
|
||||||
@ -219,14 +219,14 @@ bool JSBSim::start_JSBSim(void)
|
|||||||
// read startup to be sure it is running
|
// read startup to be sure it is running
|
||||||
char c;
|
char c;
|
||||||
if (read(jsbsim_stdout, &c, 1) != 1) {
|
if (read(jsbsim_stdout, &c, 1) != 1) {
|
||||||
hal.scheduler->panic("Unable to start JSBSim");
|
AP_HAL::panic("Unable to start JSBSim");
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!expect("JSBSim Execution beginning")) {
|
if (!expect("JSBSim Execution beginning")) {
|
||||||
hal.scheduler->panic("Failed to start JSBSim");
|
AP_HAL::panic("Failed to start JSBSim");
|
||||||
}
|
}
|
||||||
if (!open_control_socket()) {
|
if (!open_control_socket()) {
|
||||||
hal.scheduler->panic("Failed to open JSBSim control socket");
|
AP_HAL::panic("Failed to open JSBSim control socket");
|
||||||
}
|
}
|
||||||
|
|
||||||
fcntl(jsbsim_stdout, F_SETFL, fcntl(jsbsim_stdout, F_GETFL, 0) | O_NONBLOCK);
|
fcntl(jsbsim_stdout, F_SETFL, fcntl(jsbsim_stdout, F_GETFL, 0) | O_NONBLOCK);
|
||||||
|
@ -117,7 +117,7 @@ void SITL::Log_Write_SIMSTATE(DataFlash_Class *DataFlash)
|
|||||||
|
|
||||||
struct log_AHRS pkt = {
|
struct log_AHRS pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_SIMSTATE_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_SIMSTATE_MSG),
|
||||||
time_us : hal.scheduler->micros64(),
|
time_us : AP_HAL::micros64(),
|
||||||
roll : (int16_t)(state.rollDeg*100),
|
roll : (int16_t)(state.rollDeg*100),
|
||||||
pitch : (int16_t)(state.pitchDeg*100),
|
pitch : (int16_t)(state.pitchDeg*100),
|
||||||
yaw : (uint16_t)(wrap_360_cd(yaw*100)),
|
yaw : (uint16_t)(wrap_360_cd(yaw*100)),
|
||||||
|
Loading…
Reference in New Issue
Block a user