mirror of https://github.com/ArduPilot/ardupilot
SITL: make Ship simulator optional
This commit is contained in:
parent
b97e335940
commit
581629b332
|
@ -626,9 +626,12 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
|
|||
|
||||
// get speed of ground movement (for ship takeoff/landing)
|
||||
float yaw_rate = 0;
|
||||
#if AP_SIM_SHIP_ENABLED
|
||||
const Vector2f ship_movement = sitl->shipsim.get_ground_speed_adjustment(location, yaw_rate);
|
||||
const Vector3f gnd_movement(ship_movement.x, ship_movement.y, 0);
|
||||
|
||||
#else
|
||||
const Vector3f gnd_movement;
|
||||
#endif
|
||||
switch (ground_behavior) {
|
||||
case GROUND_BEHAVIOR_NONE:
|
||||
break;
|
||||
|
@ -955,7 +958,9 @@ void Aircraft::update_external_payload(const struct sitl_input &input)
|
|||
fetteconewireesc->update(*this);
|
||||
}
|
||||
|
||||
#if AP_SIM_SHIP_ENABLED
|
||||
sitl->shipsim.update();
|
||||
#endif
|
||||
|
||||
// update IntelligentEnergy 2.4kW generator
|
||||
if (ie24) {
|
||||
|
|
|
@ -17,6 +17,9 @@
|
|||
*/
|
||||
|
||||
#include "SIM_Ship.h"
|
||||
|
||||
#if AP_SIM_SHIP_ENABLED
|
||||
|
||||
#include "SITL.h"
|
||||
|
||||
#include <stdio.h>
|
||||
|
@ -205,3 +208,5 @@ void ShipSim::send_report(void)
|
|||
mav_socket.send(buf, len);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -18,6 +18,14 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef AP_SIM_SHIP_ENABLED
|
||||
#define AP_SIM_SHIP_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if AP_SIM_SHIP_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Common/Location.h>
|
||||
|
@ -84,3 +92,5 @@ private:
|
|||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // AP_SIM_SHIP_ENABLED
|
||||
|
|
|
@ -74,7 +74,9 @@ const AP_Param::GroupInfo SIM::var_info[] = {
|
|||
AP_GROUPINFO("SONAR_POS", 55, SIM, rngfnd_pos_offset, 0),
|
||||
AP_GROUPINFO("FLOW_POS", 56, SIM, optflow_pos_offset, 0),
|
||||
AP_GROUPINFO("ENGINE_FAIL", 58, SIM, engine_fail, 0),
|
||||
#if AP_SIM_SHIP_ENABLED
|
||||
AP_SUBGROUPINFO(shipsim, "SHIP_", 59, SIM, ShipSim),
|
||||
#endif
|
||||
AP_SUBGROUPEXTENSION("", 60, SIM, var_mag),
|
||||
AP_SUBGROUPEXTENSION("", 61, SIM, var_gps),
|
||||
AP_SUBGROUPEXTENSION("", 62, SIM, var_info3),
|
||||
|
|
|
@ -400,7 +400,9 @@ public:
|
|||
Sprayer sprayer_sim;
|
||||
|
||||
// simulated ship takeoffs
|
||||
#if AP_SIM_SHIP_ENABLED
|
||||
ShipSim shipsim;
|
||||
#endif
|
||||
|
||||
Gripper_Servo gripper_sim;
|
||||
Gripper_EPM gripper_epm_sim;
|
||||
|
|
Loading…
Reference in New Issue