Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL: FlightAxis Improvements #28282

Merged
merged 3 commits into from
Oct 25, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
48 changes: 40 additions & 8 deletions libraries/SITL/SIM_FlightAxis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@

#include "SIM_FlightAxis.h"

#if HAL_SIM_FLIGHTAXIS_ENABLED
#if AP_SIM_FLIGHTAXIS_ENABLED

#include <arpa/inet.h>
#include <errno.h>
Expand All @@ -36,6 +36,19 @@ extern const AP_HAL::HAL& hal;

using namespace SITL;

const AP_Param::GroupInfo FlightAxis::var_info[] = {
// @Param: OPTS
// @DisplayName: FlightAxis options
// @Description: Bitmask of FlightAxis options
// @Bitmask: 0: Reset position on startup
// @Bitmask: 1: Swap first 4 and last 4 servos (for quadplane testing)
// @Bitmask: 2: Demix heli servos and send roll/pitch/collective/yaw
// @Bitmask: 3: Don't print frame rate stats
// @User: Advanced
AP_GROUPINFO("OPTS", 1, FlightAxis, _options, uint32_t(Option::ResetPosition)),
AP_GROUPEND
};

/*
we use a thread for socket creation to reduce the impact of socket
creation latency. These condition variables are used to synchronise
Expand Down Expand Up @@ -108,10 +121,18 @@ static double timestamp_sec()
FlightAxis::FlightAxis(const char *frame_str) :
Aircraft(frame_str)
{
AP::sitl()->models.flightaxis_ptr = this;
AP_Param::setup_object_defaults(this, var_info);

use_time_sync = false;
rate_hz = 250 / target_speedup;
heli_demix = strstr(frame_str, "helidemix") != nullptr;
rev4_servos = strstr(frame_str, "rev4") != nullptr;
if(strstr(frame_str, "helidemix") != nullptr) {
_options.set(_options | uint32_t(Option::HeliDemix));
}
if(strstr(frame_str, "rev4") != nullptr) {
_options.set(_options | uint32_t(Option::Rev4Servos));
}

const char *colon = strchr(frame_str, ':');
if (colon) {
controller_ip = colon+1;
Expand Down Expand Up @@ -284,6 +305,15 @@ void FlightAxis::exchange_data(const struct sitl_input &input)
</soap:Body>
</soap:Envelope>)");
soap_request_end(1000);
if(option_is_set(Option::ResetPosition)) {
soap_request_start("ResetAircraft", R"(<?xml version='1.0' encoding='UTF-8'?>
<soap:Envelope xmlns:soap='http://schemas.xmlsoap.org/soap/envelope/' xmlns:xsd='http://www.w3.org/2001/XMLSchema' xmlns:xsi='http://www.w3.org/2001/XMLSchema-instance'>
<soap:Body>
<ResetAircraft><a>1</a><b>2</b></ResetAircraft>
</soap:Body>
</soap:Envelope>)");
soap_request_end(1000);
}
soap_request_start("InjectUAVControllerInterface", R"(<?xml version='1.0' encoding='UTF-8'?>
<soap:Envelope xmlns:soap='http://schemas.xmlsoap.org/soap/envelope/' xmlns:xsd='http://www.w3.org/2001/XMLSchema' xmlns:xsi='http://www.w3.org/2001/XMLSchema-instance'>
<soap:Body>
Expand All @@ -301,15 +331,15 @@ void FlightAxis::exchange_data(const struct sitl_input &input)
scaled_servos[i] = (input.servos[i] - 1000) / 1000.0f;
}

if (rev4_servos) {
if (option_is_set(Option::Rev4Servos)) {
// swap first 4 and last 4 servos, for quadplane testing
float saved[4];
memcpy(saved, &scaled_servos[0], sizeof(saved));
memcpy(&scaled_servos[0], &scaled_servos[4], sizeof(saved));
memcpy(&scaled_servos[4], saved, sizeof(saved));
}

if (heli_demix) {
if (option_is_set(Option::HeliDemix)) {
// FlightAxis expects "roll/pitch/collective/yaw" input
float swash1 = scaled_servos[0];
float swash2 = scaled_servos[1];
Expand Down Expand Up @@ -574,8 +604,10 @@ void FlightAxis::report_FPS(void)
uint64_t frames = socket_frame_counter - last_socket_frame_counter;
last_socket_frame_counter = socket_frame_counter;
double dt = state.m_currentPhysicsTime_SEC - last_frame_count_s;
printf("%.2f/%.2f FPS avg=%.2f glitches=%u\n",
frames / dt, 1000 / dt, 1.0/average_frame_time_s, unsigned(glitch_count));
if(!option_is_set(Option::SilenceFPS)) {
printf("%.2f/%.2f FPS avg=%.2f glitches=%u\n",
frames / dt, 1000 / dt, 1.0/average_frame_time_s, unsigned(glitch_count));
}
} else {
printf("Initial position %f %f %f\n", position.x, position.y, position.z);
}
Expand Down Expand Up @@ -615,4 +647,4 @@ void FlightAxis::socket_creator(void)
}
}

#endif // HAL_SIM_FLIGHTAXIS_ENABLED
#endif // AP_SIM_FLIGHTAXIS_ENABLED
27 changes: 19 additions & 8 deletions libraries/SITL/SIM_FlightAxis.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,9 @@
#pragma once

#include <AP_HAL/AP_HAL_Boards.h>
#include "SIM_config.h"

#ifndef HAL_SIM_FLIGHTAXIS_ENABLED
#define HAL_SIM_FLIGHTAXIS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif

#if HAL_SIM_FLIGHTAXIS_ENABLED
#if AP_SIM_FLIGHTAXIS_ENABLED

#include <AP_HAL/utility/Socket_native.h>

Expand All @@ -39,6 +36,8 @@ class FlightAxis : public Aircraft {
public:
FlightAxis(const char *frame_str);

static const struct AP_Param::GroupInfo var_info[];

/* update model by one time step */
void update(const struct sitl_input &input) override;

Expand Down Expand Up @@ -175,12 +174,24 @@ class FlightAxis : public Aircraft {

struct sitl_input last_input;

AP_Int32 _options;

enum class Option : uint32_t{
ResetPosition = (1U<<0),
Rev4Servos = (1U<<1),
HeliDemix = (1U<<2),
SilenceFPS = (1U<<3),
};

// return true if an option is set
bool option_is_set(Option option) const {
return (uint32_t(option) & uint32_t(_options)) != 0;
}

double average_frame_time_s;
double extrapolated_s;
double initial_time_s;
double last_time_s;
bool heli_demix;
bool rev4_servos;
bool controller_started;
uint32_t glitch_count;
uint64_t frame_counter;
Expand All @@ -204,4 +215,4 @@ class FlightAxis : public Aircraft {

} // namespace SITL

#endif // HAL_SIM_FLIGHTAXIS_ENABLED
#endif // AP_SIM_FLIGHTAXIS_ENABLED
4 changes: 4 additions & 0 deletions libraries/SITL/SIM_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,10 @@
#define AP_SIM_SLUNGPAYLOAD_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif

#ifndef AP_SIM_FLIGHTAXIS_ENABLED
#define AP_SIM_FLIGHTAXIS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif

#ifndef AP_SIM_TSYS03_ENABLED
#define AP_SIM_TSYS03_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif
Expand Down
7 changes: 7 additions & 0 deletions libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@

#include "SIM_StratoBlimp.h"
#include "SIM_Glider.h"
#include "SIM_FlightAxis.h"

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -1487,6 +1488,12 @@ const AP_Param::GroupInfo SIM::ModelParm::var_info[] = {
AP_SUBGROUPINFO(slung_payload_sim, "SLUP_", 4, SIM::ModelParm, SlungPayloadSim),
#endif

#if AP_SIM_FLIGHTAXIS_ENABLED
// @Group: RFL_
// @Path: ./SIM_FlightAxis.cpp
AP_SUBGROUPPTR(flightaxis_ptr, "RFL_", 5, SIM::ModelParm, FlightAxis),
#endif

AP_GROUPEND
};

Expand Down
4 changes: 4 additions & 0 deletions libraries/SITL/SITL.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ struct float_array {

class StratoBlimp;
class Glider;
class FlightAxis;

struct sitl_fdm {
// this is the structure passed between FDM models and the main SITL code
Expand Down Expand Up @@ -326,6 +327,9 @@ class SIM {
#endif
#if AP_SIM_SLUNGPAYLOAD_ENABLED
SlungPayloadSim slung_payload_sim;
#endif
#if AP_SIM_FLIGHTAXIS_ENABLED
FlightAxis *flightaxis_ptr;
#endif
};
ModelParm models;
Expand Down
Loading