SITL: remove home_str from constructor
This commit is contained in:
parent
cdab58d598
commit
f7b47679bb
@ -16,8 +16,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
AirSim::AirSim(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
AirSim::AirSim(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
sock(true)
|
||||
{
|
||||
printf("Starting SITL Airsim\n");
|
||||
|
@ -15,14 +15,14 @@ namespace SITL {
|
||||
|
||||
class AirSim : public Aircraft {
|
||||
public:
|
||||
AirSim(const char *home_str, const char *frame_str);
|
||||
AirSim(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new AirSim(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new AirSim(frame_str);
|
||||
}
|
||||
|
||||
/* Create and set in/out socket for Airsim simulator */
|
||||
|
@ -38,7 +38,7 @@ using namespace SITL;
|
||||
parent class for all simulator types
|
||||
*/
|
||||
|
||||
Aircraft::Aircraft(const char *home_str, const char *frame_str) :
|
||||
Aircraft::Aircraft(const char *frame_str) :
|
||||
ground_level(0.0f),
|
||||
frame_height(0.0f),
|
||||
dcm(),
|
||||
@ -63,6 +63,19 @@ Aircraft::Aircraft(const char *home_str, const char *frame_str) :
|
||||
// make the SIM_* variables available to simulator backends
|
||||
sitl = AP::sitl();
|
||||
|
||||
set_speedup(1.0f);
|
||||
|
||||
last_wall_time_us = get_wall_time_us();
|
||||
frame_counter = 0;
|
||||
|
||||
// allow for orientation settings, such as with tailsitters
|
||||
enum ap_var_type ptype;
|
||||
ahrs_orientation = (AP_Int8 *)AP_Param::find("AHRS_ORIENTATION", &ptype);
|
||||
terrain = reinterpret_cast<AP_Terrain *>(AP_Param::find_object("TERRAIN_"));
|
||||
}
|
||||
|
||||
void Aircraft::set_start_location(const char *home_str)
|
||||
{
|
||||
if (!parse_home(home_str, home, home_yaw)) {
|
||||
::printf("Failed to parse home string (%s). Should be LAT,LON,ALT,HDG e.g. 37.4003371,-122.0800351,0,353\n", home_str);
|
||||
}
|
||||
@ -75,19 +88,8 @@ Aircraft::Aircraft(const char *home_str, const char *frame_str) :
|
||||
ground_level = home.alt * 0.01f;
|
||||
|
||||
dcm.from_euler(0.0f, 0.0f, radians(home_yaw));
|
||||
|
||||
set_speedup(1.0f);
|
||||
|
||||
last_wall_time_us = get_wall_time_us();
|
||||
frame_counter = 0;
|
||||
|
||||
// allow for orientation settings, such as with tailsitters
|
||||
enum ap_var_type ptype;
|
||||
ahrs_orientation = (AP_Int8 *)AP_Param::find("AHRS_ORIENTATION", &ptype);
|
||||
terrain = reinterpret_cast<AP_Terrain *>(AP_Param::find_object("TERRAIN_"));
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
parse a home string into a location and yaw
|
||||
*/
|
||||
|
@ -37,7 +37,10 @@ namespace SITL {
|
||||
*/
|
||||
class Aircraft {
|
||||
public:
|
||||
Aircraft(const char *home_str, const char *frame_str);
|
||||
Aircraft(const char *frame_str);
|
||||
|
||||
// called directly after constructor:
|
||||
virtual void set_start_location(const char *home_str);
|
||||
|
||||
/*
|
||||
set simulation speedup
|
||||
|
@ -23,8 +23,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
namespace SITL {
|
||||
|
||||
BalanceBot::BalanceBot(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
BalanceBot::BalanceBot(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
skid_turn_rate(140) // degrees/sec
|
||||
{
|
||||
dcm.from_euler(0,0,0); // initial yaw, pitch and roll in radians
|
||||
|
@ -24,14 +24,14 @@ namespace SITL {
|
||||
|
||||
class BalanceBot : public Aircraft {
|
||||
public:
|
||||
BalanceBot(const char *home_str, const char *frame_str);
|
||||
BalanceBot(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new BalanceBot(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new BalanceBot(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -22,8 +22,8 @@
|
||||
|
||||
namespace SITL {
|
||||
|
||||
Balloon::Balloon(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
Balloon::Balloon(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{
|
||||
mass = 5.0f;
|
||||
}
|
||||
|
@ -27,14 +27,14 @@ namespace SITL {
|
||||
*/
|
||||
class Balloon : public Aircraft {
|
||||
public:
|
||||
Balloon(const char *home_str, const char *frame_str);
|
||||
Balloon(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Balloon(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Balloon(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -26,8 +26,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
namespace SITL {
|
||||
|
||||
CRRCSim::CRRCSim(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
CRRCSim::CRRCSim(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
last_timestamp(0),
|
||||
sock(true)
|
||||
{
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class CRRCSim : public Aircraft {
|
||||
public:
|
||||
CRRCSim(const char *home_str, const char *frame_str);
|
||||
CRRCSim(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new CRRCSim(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new CRRCSim(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -24,8 +24,8 @@
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
SITL::Calibration::Calibration(const char *home_str, const char *frame_str)
|
||||
: Aircraft(home_str, frame_str)
|
||||
SITL::Calibration::Calibration(const char *frame_str)
|
||||
: Aircraft(frame_str)
|
||||
{
|
||||
mass = 1.5f;
|
||||
}
|
||||
|
@ -64,12 +64,12 @@ namespace SITL {
|
||||
*/
|
||||
class Calibration : public Aircraft {
|
||||
public:
|
||||
Calibration(const char *home_str, const char *frame_str);
|
||||
Calibration(const char *frame_str);
|
||||
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Calibration(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Calibration(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -82,8 +82,8 @@ static const struct {
|
||||
};
|
||||
|
||||
|
||||
FlightAxis::FlightAxis(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
FlightAxis::FlightAxis(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{
|
||||
use_time_sync = false;
|
||||
rate_hz = 250 / target_speedup;
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class FlightAxis : public Aircraft {
|
||||
public:
|
||||
FlightAxis(const char *home_str, const char *frame_str);
|
||||
FlightAxis(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new FlightAxis(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new FlightAxis(frame_str);
|
||||
}
|
||||
|
||||
struct state {
|
||||
|
@ -27,8 +27,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
namespace SITL {
|
||||
|
||||
Gazebo::Gazebo(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
Gazebo::Gazebo(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
last_timestamp(0),
|
||||
socket_sitl{true}
|
||||
{
|
||||
|
@ -28,14 +28,14 @@ namespace SITL {
|
||||
*/
|
||||
class Gazebo : public Aircraft {
|
||||
public:
|
||||
Gazebo(const char *home_str, const char *frame_str);
|
||||
Gazebo(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Gazebo(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Gazebo(frame_str);
|
||||
}
|
||||
|
||||
/* Create and set in/out socket for Gazebo simulator */
|
||||
|
@ -22,8 +22,8 @@
|
||||
|
||||
namespace SITL {
|
||||
|
||||
Helicopter::Helicopter(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
Helicopter::Helicopter(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{
|
||||
mass = 2.13f;
|
||||
|
||||
|
@ -27,14 +27,14 @@ namespace SITL {
|
||||
*/
|
||||
class Helicopter : public Aircraft {
|
||||
public:
|
||||
Helicopter(const char *home_str, const char *frame_str);
|
||||
Helicopter(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Helicopter(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Helicopter(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -36,8 +36,8 @@ namespace SITL {
|
||||
|
||||
#define DEBUG_JSBSIM 1
|
||||
|
||||
JSBSim::JSBSim(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
JSBSim::JSBSim(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
sock_control(false),
|
||||
sock_fgfdm(true),
|
||||
initialised(false),
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class JSBSim : public Aircraft {
|
||||
public:
|
||||
JSBSim(const char *home_str, const char *frame_str);
|
||||
JSBSim(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new JSBSim(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new JSBSim(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -80,8 +80,8 @@ static const struct {
|
||||
};
|
||||
|
||||
|
||||
Morse::Morse(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
Morse::Morse(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{
|
||||
char *saveptr = nullptr;
|
||||
char *s = strdup(frame_str);
|
||||
|
@ -28,14 +28,14 @@ namespace SITL {
|
||||
*/
|
||||
class Morse : public Aircraft {
|
||||
public:
|
||||
Morse(const char *home_str, const char *frame_str);
|
||||
Morse(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Morse(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Morse(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -23,8 +23,8 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
MultiCopter::MultiCopter(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
MultiCopter::MultiCopter(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
frame(nullptr)
|
||||
{
|
||||
mass = 1.5f;
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class MultiCopter : public Aircraft {
|
||||
public:
|
||||
MultiCopter(const char *home_str, const char *frame_str);
|
||||
MultiCopter(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new MultiCopter(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new MultiCopter(frame_str);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
@ -23,8 +23,8 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
Plane::Plane(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
Plane::Plane(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{
|
||||
mass = 2.0f;
|
||||
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class Plane : public Aircraft {
|
||||
public:
|
||||
Plane(const char *home_str, const char *frame_str);
|
||||
Plane(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
virtual void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Plane(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Plane(frame_str);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
@ -22,8 +22,8 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
QuadPlane::QuadPlane(const char *home_str, const char *frame_str) :
|
||||
Plane(home_str, frame_str)
|
||||
QuadPlane::QuadPlane(const char *frame_str) :
|
||||
Plane(frame_str)
|
||||
{
|
||||
// default to X frame
|
||||
const char *frame_type = "x";
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class QuadPlane : public Plane {
|
||||
public:
|
||||
QuadPlane(const char *home_str, const char *frame_str);
|
||||
QuadPlane(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new QuadPlane(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new QuadPlane(frame_str);
|
||||
}
|
||||
private:
|
||||
Frame *frame;
|
||||
|
@ -23,8 +23,8 @@
|
||||
|
||||
namespace SITL {
|
||||
|
||||
SimRover::SimRover(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
SimRover::SimRover(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
max_speed(20),
|
||||
max_accel(10),
|
||||
max_wheel_turn(35),
|
||||
|
@ -27,14 +27,14 @@ namespace SITL {
|
||||
*/
|
||||
class SimRover : public Aircraft {
|
||||
public:
|
||||
SimRover(const char *home_str, const char *frame_str);
|
||||
SimRover(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new SimRover(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new SimRover(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -38,8 +38,8 @@ namespace SITL {
|
||||
#define WAVE_ANGLE_GAIN 1
|
||||
#define WAVE_HEAVE_GAIN 1
|
||||
|
||||
Sailboat::Sailboat(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
Sailboat::Sailboat(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
steering_angle_max(35),
|
||||
turning_circle(1.8)
|
||||
{
|
||||
|
@ -27,14 +27,14 @@ namespace SITL {
|
||||
*/
|
||||
class Sailboat : public Aircraft {
|
||||
public:
|
||||
Sailboat(const char *home_str, const char *frame_str);
|
||||
Sailboat(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Sailboat(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Sailboat(frame_str);
|
||||
}
|
||||
|
||||
bool on_ground() const override {return true;};
|
||||
|
@ -35,8 +35,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
namespace SITL {
|
||||
|
||||
Scrimmage::Scrimmage(const char *home_str, const char *_frame_str) :
|
||||
Aircraft(home_str, _frame_str),
|
||||
Scrimmage::Scrimmage(const char *_frame_str) :
|
||||
Aircraft(_frame_str),
|
||||
prev_timestamp_us(0),
|
||||
recv_sock(true),
|
||||
send_sock(true),
|
||||
|
@ -32,14 +32,14 @@ namespace SITL {
|
||||
*/
|
||||
class Scrimmage : public Aircraft {
|
||||
public:
|
||||
Scrimmage(const char *home_str, const char *frame_str);
|
||||
Scrimmage(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Scrimmage(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Scrimmage(frame_str);
|
||||
}
|
||||
|
||||
void set_config(const char *config) override;
|
||||
|
@ -51,8 +51,8 @@ static const struct {
|
||||
{ "INS_ACCSCAL_Z", 1.001 },
|
||||
};
|
||||
|
||||
SilentWings::SilentWings(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
SilentWings::SilentWings(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
last_data_time_ms(0),
|
||||
first_pkt_timestamp_ms(0),
|
||||
time_base_us(0),
|
||||
|
@ -26,14 +26,14 @@ namespace SITL {
|
||||
*/
|
||||
class SilentWings : public Aircraft {
|
||||
public:
|
||||
SilentWings(const char *home_str, const char *frame_str);
|
||||
SilentWings(const char *frame_str);
|
||||
|
||||
/* Updates the aircraft model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* Static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new SilentWings(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new SilentWings(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -22,8 +22,8 @@
|
||||
|
||||
using namespace SITL;
|
||||
|
||||
SingleCopter::SingleCopter(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
SingleCopter::SingleCopter(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{
|
||||
mass = 2.0f;
|
||||
|
||||
|
@ -28,14 +28,14 @@ namespace SITL {
|
||||
*/
|
||||
class SingleCopter : public Aircraft {
|
||||
public:
|
||||
SingleCopter(const char *home_str, const char *frame_str);
|
||||
SingleCopter(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new SingleCopter(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new SingleCopter(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -35,8 +35,8 @@ static Thruster vectored_thrusters[] =
|
||||
|
||||
};
|
||||
|
||||
Submarine::Submarine(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
Submarine::Submarine(const char *frame_str) :
|
||||
Aircraft(frame_str),
|
||||
frame(NULL)
|
||||
{
|
||||
frame_height = 0.0;
|
||||
|
@ -31,14 +31,14 @@ namespace SITL {
|
||||
|
||||
class Submarine : public Aircraft {
|
||||
public:
|
||||
Submarine(const char *home_str, const char *frame_str);
|
||||
Submarine(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Submarine(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Submarine(frame_str);
|
||||
}
|
||||
|
||||
|
||||
|
@ -22,8 +22,8 @@
|
||||
|
||||
namespace SITL {
|
||||
|
||||
Tracker::Tracker(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
Tracker::Tracker(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{}
|
||||
|
||||
|
||||
|
@ -27,12 +27,12 @@ namespace SITL {
|
||||
*/
|
||||
class Tracker : public Aircraft {
|
||||
public:
|
||||
Tracker(const char *home_str, const char *frame_str);
|
||||
Tracker(const char *frame_str);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Tracker(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new Tracker(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -32,8 +32,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
namespace SITL {
|
||||
|
||||
XPlane::XPlane(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str)
|
||||
XPlane::XPlane(const char *frame_str) :
|
||||
Aircraft(frame_str)
|
||||
{
|
||||
use_time_sync = false;
|
||||
const char *colon = strchr(frame_str, ':');
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class XPlane : public Aircraft {
|
||||
public:
|
||||
XPlane(const char *home_str, const char *frame_str);
|
||||
XPlane(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new XPlane(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new XPlane(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
@ -29,8 +29,8 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
namespace SITL {
|
||||
|
||||
last_letter::last_letter(const char *home_str, const char *_frame_str) :
|
||||
Aircraft(home_str, _frame_str),
|
||||
last_letter::last_letter(const char *_frame_str) :
|
||||
Aircraft(_frame_str),
|
||||
last_timestamp_us(0),
|
||||
sock(true)
|
||||
{
|
||||
|
@ -29,14 +29,14 @@ namespace SITL {
|
||||
*/
|
||||
class last_letter : public Aircraft {
|
||||
public:
|
||||
last_letter(const char *home_str, const char *frame_str);
|
||||
last_letter(const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new last_letter(home_str, frame_str);
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new last_letter(frame_str);
|
||||
}
|
||||
|
||||
private:
|
||||
|
Loading…
Reference in New Issue
Block a user