2015-05-22 02:52:45 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
simulator connection for ardupilot version of last_letter
|
|
|
|
*/
|
|
|
|
|
2015-10-22 11:04:23 -03:00
|
|
|
#pragma once
|
2015-05-22 02:52:45 -03:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/utility/Socket.h>
|
2015-05-22 02:52:45 -03:00
|
|
|
|
2015-10-22 10:58:33 -03:00
|
|
|
#include "SIM_Aircraft.h"
|
|
|
|
|
2015-10-22 10:04:42 -03:00
|
|
|
namespace SITL {
|
|
|
|
|
2015-05-22 02:52:45 -03:00
|
|
|
/*
|
|
|
|
a last_letter simulator
|
|
|
|
*/
|
2015-10-22 10:15:34 -03:00
|
|
|
class last_letter : public Aircraft {
|
2015-05-22 02:52:45 -03:00
|
|
|
public:
|
|
|
|
last_letter(const char *home_str, const char *frame_str);
|
|
|
|
|
|
|
|
/* update model by one time step */
|
2019-02-21 19:12:05 -04:00
|
|
|
void update(const struct sitl_input &input) override;
|
2015-05-22 02:52:45 -03:00
|
|
|
|
|
|
|
/* static object creator */
|
|
|
|
static Aircraft *create(const char *home_str, const char *frame_str) {
|
|
|
|
return new last_letter(home_str, frame_str);
|
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
2016-10-16 11:35:14 -03:00
|
|
|
static const uint16_t fdm_port = 5002;
|
2015-05-22 02:52:45 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
packet sent to last_letter
|
|
|
|
*/
|
|
|
|
struct servo_packet {
|
|
|
|
uint16_t servos[16];
|
|
|
|
};
|
2015-10-22 10:15:20 -03:00
|
|
|
|
2015-05-22 02:52:45 -03:00
|
|
|
/*
|
|
|
|
reply packet sent from last_letter to ArduPilot
|
|
|
|
*/
|
|
|
|
struct fdm_packet {
|
|
|
|
uint64_t timestamp_us; // simulation time in microseconds
|
|
|
|
double latitude, longitude;
|
|
|
|
double altitude;
|
|
|
|
double heading;
|
|
|
|
double speedN, speedE, speedD;
|
|
|
|
double xAccel, yAccel, zAccel;
|
|
|
|
double rollRate, pitchRate, yawRate;
|
|
|
|
double roll, pitch, yaw;
|
|
|
|
double airspeed;
|
|
|
|
};
|
|
|
|
|
|
|
|
void recv_fdm(const struct sitl_input &input);
|
|
|
|
void send_servos(const struct sitl_input &input);
|
|
|
|
void start_last_letter(void);
|
|
|
|
|
|
|
|
uint64_t last_timestamp_us;
|
|
|
|
SocketAPM sock;
|
|
|
|
};
|
|
|
|
|
2015-10-22 10:04:42 -03:00
|
|
|
} // namespace SITL
|