21 #include <arpa/inet.h> 27 #include <sys/types.h> 38 #pragma GCC diagnostic ignored "-Wunused-result" 44 {
"AHRS_EKF_TYPE", 10 },
46 {
"SERVO1_MIN", 1000 },
47 {
"SERVO1_MAX", 2000 },
48 {
"SERVO2_MIN", 1000 },
49 {
"SERVO2_MAX", 2000 },
50 {
"SERVO3_MIN", 1000 },
51 {
"SERVO3_MAX", 2000 },
52 {
"SERVO4_MIN", 1000 },
53 {
"SERVO4_MAX", 2000 },
54 {
"SERVO5_MIN", 1000 },
55 {
"SERVO5_MAX", 2000 },
56 {
"SERVO6_MIN", 1000 },
57 {
"SERVO6_MAX", 2000 },
58 {
"SERVO6_MIN", 1000 },
59 {
"SERVO6_MAX", 2000 },
60 {
"INS_ACC2OFFS_X", 0.001 },
61 {
"INS_ACC2OFFS_Y", 0.001 },
62 {
"INS_ACC2OFFS_Z", 0.001 },
63 {
"INS_ACC2SCAL_X", 1.001 },
64 {
"INS_ACC2SCAL_Y", 1.001 },
65 {
"INS_ACC2SCAL_Z", 1.001 },
66 {
"INS_ACCOFFS_X", 0.001 },
67 {
"INS_ACCOFFS_Y", 0.001 },
68 {
"INS_ACCOFFS_Z", 0.001 },
69 {
"INS_ACCSCAL_X", 1.001 },
70 {
"INS_ACCSCAL_Y", 1.001 },
71 {
"INS_ACCSCAL_Z", 1.001 },
80 heli_demix = strstr(frame_str,
"helidemix") !=
nullptr;
82 const char *colon = strchr(frame_str,
':');
106 #if defined(__CYGWIN__) || defined(__CYGWIN64__) 108 #elif defined(__APPLE__) && defined(__MACH__) 109 pthread_setname_np(
"ardupilot-flightaxis");
111 pthread_setname_np(pthread_self(),
"ardupilot-flightaxis");
137 const char *reply0 = reply;
138 for (uint16_t i=0; i<
num_keys; i++) {
139 const char *p = strstr(reply,
keytable[i].key);
141 p = strstr(reply0,
keytable[i].key);
150 if (strncmp(p,
"true", 4) == 0) {
152 }
else if (strncmp(p,
"false", 5) == 0) {
182 SocketAPM sock(
false);
187 sock.set_blocking(
false);
193 content-type: text/xml;charset='UTF-8' 194 Connection: Keep-Alive 198 (unsigned)strlen(req1), req1);
199 sock.send(req, strlen(req));
203 memset(reply, 0,
sizeof(reply));
204 ssize_t ret = sock.recv(reply,
sizeof(reply)-1, 1000);
209 char *p = strstr(reply,
"Content-Length: ");
211 printf(
"No Content-Length\n");
216 uint32_t content_length = strtoul(p+16,
nullptr, 10);
217 char *body = strstr(p,
"\r\n\r\n");
218 if (body ==
nullptr) {
225 int32_t expected_length = content_length + (body - reply);
226 if (expected_length >= (int32_t)
sizeof(reply)) {
227 printf(
"Reply too large %i\n", expected_length);
230 while (ret < expected_length) {
231 ssize_t ret2 = sock.recv(&reply[ret],
sizeof(reply)-(1+ret), 100);
239 return strdup(reply);
251 char *reply =
soap_request(
"RestoreOriginalControllerDevice", R
"(<?xml version='1.0' encoding='UTF-8'?> 252 <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'> 254 <RestoreOriginalControllerDevice><a>1</a><b>2</b></RestoreOriginalControllerDevice> 258 reply = soap_request("InjectUAVControllerInterface", R
"(<?xml version='1.0' encoding='UTF-8'?> 259 <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'> 261 <InjectUAVControllerInterface><a>1</a><b>2</b></InjectUAVControllerInterface> 269 float scaled_servos[8];
270 for (uint8_t i=0; i<8; i++) {
271 scaled_servos[i] = (input.
servos[i] - 1000) / 1000.0
f;
277 memcpy(saved, &scaled_servos[0],
sizeof(saved));
278 memcpy(&scaled_servos[0], &scaled_servos[4],
sizeof(saved));
279 memcpy(&scaled_servos[4], saved,
sizeof(saved));
284 float swash1 = scaled_servos[0];
285 float swash2 = scaled_servos[1];
286 float swash3 = scaled_servos[2];
288 float roll_rate = swash1 - swash2;
289 float pitch_rate = -((swash1+swash2) / 2.0
f - swash3);
296 char *reply =
soap_request(
"ExchangeData", 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'> 300 <m-selectedChannels>255</m-selectedChannels> 301 <m-channelValues-0to1> 310 </m-channelValues-0to1> 329 if (dt > 0 && dt < 0.1) {
352 if (dt_seconds < 0) {
360 if (dt_seconds < 0.00001
f) {
361 float delta_time = 0.001;
366 if (delta_time <= 0) {
376 usleep(delta_time*1.0e6);
453 if (dt_us > 500000) {
482 printf(
"%.2f/%.2f FPS avg=%.2f\n",
int printf(const char *fmt,...)
struct sitl_input last_input
Vector3< float > Vector3f
int vasprintf(char **strp, const char *fmt, va_list ap)
double m_heliMainRotorRPM
double m_pitchRate_DEGpSEC
void parse_reply(const char *reply)
AP_HAL::Semaphore * mutex
double m_orientationQuaternion_Y
double m_currentPhysicsTime_SEC
double m_isTouchingGround
double m_orientationQuaternion_Z
#define HAL_SEMAPHORE_BLOCK_FOREVER
double m_rollRate_DEGpSEC
double m_batteryVoltage_VOLTS
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
virtual Semaphore * new_semaphore(void)
double m_accelerationBodyAZ_MPS2
uint64_t activation_frame_counter
static void * update_thread(void *arg)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Matrix3< T > transposed(void) const
FlightAxis(const char *home_str, const char *frame_str)
double m_orientationQuaternion_W
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
bool is_zero(const T fVal1)
double m_batteryCurrentDraw_AMPS
double m_aircraftPositionX_MTR
void rotation_matrix(Matrix3f &m) const
const char * controller_ip
uint64_t socket_frame_counter
Vector3f last_velocity_ef
double m_velocityWorldV_MPS
void update_mag_field_bf(void)
static const struct @202 sim_defaults[]
double m_flightAxisControllerIsActive
float constrain_float(const float amt, const float low, const float high)
double m_velocityWorldU_MPS
void update_position(void)
char * soap_request(const char *action, const char *fmt,...)
double m_velocityWorldW_MPS
static constexpr float radians(float deg)
void extrapolate_sensors(float delta_time)
int asprintf(char **strp, const char *fmt,...)
double m_accelerationBodyAY_MPS2
double m_accelerationBodyAX_MPS2
void panic(const char *errormsg,...) FMT_PRINTF(1
static const uint16_t num_keys
void exchange_data(const struct sitl_input &input)
double last_frame_count_s
double m_aircraftPositionY_MTR
double average_frame_time_s
uint64_t last_socket_frame_counter
double m_orientationQuaternion_X
void update(const struct sitl_input &input)
double m_resetButtonHasBeenPressed
static bool set_default_by_name(const char *name, float value)