ardupilot/libraries/SITL/SIM_CRRCSim.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

90 lines
2.2 KiB
C
Raw Normal View History

/*
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 CRRCSim
*/
#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#ifndef HAL_SIM_CRRCSIM_ENABLED
#define HAL_SIM_CRRCSIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif
#if HAL_SIM_CRRCSIM_ENABLED
2023-12-25 22:21:11 -04:00
#include <AP_HAL/utility/Socket_native.h>
#include "SIM_Aircraft.h"
2015-10-22 10:04:42 -03:00
namespace SITL {
/*
a CRRCSim simulator
*/
class CRRCSim : public Aircraft {
public:
2019-08-15 01:01:24 -03:00
CRRCSim(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;
/* static object creator */
2019-08-15 01:01:24 -03:00
static Aircraft *create(const char *frame_str) {
return NEW_NOTHROW CRRCSim(frame_str);
}
private:
/*
packet sent to CRRCSim
*/
struct servo_packet {
float roll_rate;
float pitch_rate;
float throttle;
float yaw_rate;
float col_pitch;
};
2015-10-22 10:15:20 -03:00
/*
reply packet sent from CRRCSim to ArduPilot
*/
struct fdm_packet {
double timestamp;
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 send_servos_heli(const struct sitl_input &input);
void send_servos_fixed_wing(const struct sitl_input &input);
void recv_fdm(const struct sitl_input &input);
void send_servos(const struct sitl_input &input);
bool heli_servos;
double last_timestamp;
2023-12-25 22:21:11 -04:00
SocketAPM_native sock;
};
2015-10-22 10:04:42 -03:00
} // namespace SITL
#endif // HAL_SIM_CRRCSIM_ENABLED