mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
SITL: provide HAL_x_ENABLED for many SITL features
This allows for the feature to be compiled out
This commit is contained in:
parent
918218bdd4
commit
90f8cbde13
@ -17,6 +17,9 @@
|
||||
*/
|
||||
|
||||
#include "SIM_ADSB.h"
|
||||
|
||||
#if HAL_SIM_ADSB_ENABLED
|
||||
|
||||
#include "SITL.h"
|
||||
|
||||
#include <stdio.h>
|
||||
@ -270,3 +273,5 @@ void ADSB::send_report(void)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_ADSB_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_ADSB_ENABLED
|
||||
#define HAL_SIM_ADSB_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_ADSB_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -79,3 +87,5 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_ADSB_ENABLED
|
||||
|
@ -21,8 +21,10 @@
|
||||
*/
|
||||
|
||||
#include "SIM_AIS.h"
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
#if HAL_SIM_AIS_ENABLED
|
||||
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -73,3 +75,5 @@ void AIS::update()
|
||||
write_to_autopilot(line, strlen(line));
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_AIS_ENABLED
|
||||
|
@ -22,6 +22,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_AIS_ENABLED
|
||||
#define HAL_SIM_AIS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_AIS_ENABLED
|
||||
|
||||
#include "SIM_SerialDevice.h"
|
||||
#include <SITL/SITL.h>
|
||||
|
||||
@ -42,3 +50,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_AIS_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_AirSim.h"
|
||||
|
||||
#if HAL_SIM_AIRSIM_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <errno.h>
|
||||
@ -423,3 +425,5 @@ void AirSim::report_FPS(void)
|
||||
last_frame_count = state.timestamp;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_AIRSIM_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_AIRSIM_ENABLED
|
||||
#define HAL_SIM_AIRSIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_AIRSIM_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include "SIM_Aircraft.h"
|
||||
|
||||
@ -150,3 +158,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_AIRSIM_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_CRRCSim.h"
|
||||
|
||||
#if HAL_SIM_CRRCSIM_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
@ -154,3 +156,5 @@ void CRRCSim::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_CRRCSIM_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#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
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -77,3 +85,5 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_CRRCSIM_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_FlightAxis.h"
|
||||
|
||||
#if HAL_SIM_FLIGHTAXIS_ENABLED
|
||||
|
||||
#include <arpa/inet.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
@ -588,3 +590,5 @@ void FlightAxis::socket_creator(void)
|
||||
pthread_mutex_unlock(&sockmtx);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_FLIGHTAXIS_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_FLIGHTAXIS_ENABLED
|
||||
#define HAL_SIM_FLIGHTAXIS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_FLIGHTAXIS_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -194,3 +202,5 @@ private:
|
||||
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_FLIGHTAXIS_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_Gazebo.h"
|
||||
|
||||
#if HAL_SIM_GAZEBO_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
|
||||
@ -171,3 +173,6 @@ void Gazebo::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
|
||||
#endif // HAL_SIM_GAZEBO_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_GAZEBO_ENABLED
|
||||
#define HAL_SIM_GAZEBO_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_GAZEBO_ENABLED
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
@ -75,3 +83,6 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
|
||||
#endif // HAL_SIM_GAZEBO_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_Gimbal.h"
|
||||
|
||||
#if HAL_SIM_GIMBAL_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -413,3 +415,5 @@ void Gimbal::send_report(void)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_GIMBAL_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_GIMBAL_ENABLED
|
||||
#define HAL_SIM_GIMBAL_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_GIMBAL_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -111,3 +119,5 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_GIMBAL_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_JSBSim.h"
|
||||
|
||||
#if HAL_SIM_JSBSIM_ENABLED
|
||||
|
||||
#include <arpa/inet.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
@ -482,3 +484,5 @@ void JSBSim::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_JSBSIM_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_JSBSIM_ENABLED
|
||||
#define HAL_SIM_JSBSIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_JSBSIM_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -176,3 +184,5 @@ public:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_JSBSIM_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_JSON.h"
|
||||
|
||||
#if HAL_SIM_JSON_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <errno.h>
|
||||
@ -448,3 +450,5 @@ void JSON::update(const struct sitl_input &input)
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_JSON_ENABLED
|
||||
|
@ -14,6 +14,14 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_JSON_ENABLED
|
||||
#define HAL_SIM_JSON_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_JSON_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include "SIM_Aircraft.h"
|
||||
|
||||
@ -143,3 +151,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_JSON_ENABLED
|
||||
|
@ -17,6 +17,9 @@
|
||||
*/
|
||||
|
||||
#include "SIM_JSON_Master.h"
|
||||
|
||||
#if HAL_SIM_JSON_MASTER_ENABLED
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <errno.h>
|
||||
|
||||
@ -183,3 +186,6 @@ void JSON_Master::send(const struct sitl_fdm &output, const Vector3d &position)
|
||||
list->sock_out.send(json_out,length);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif // HAL_SIM_JSON_MASTER_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_JSON_MASTER_ENABLED
|
||||
#define HAL_SIM_JSON_MASTER_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_JSON_MASTER_ENABLED
|
||||
|
||||
#include "SITL_Input.h"
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
@ -54,3 +62,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_JSON_MASTER_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_Morse.h"
|
||||
|
||||
#if HAL_SIM_MORSE_ENABLED
|
||||
|
||||
#include <arpa/inet.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
@ -671,3 +673,5 @@ void Morse::send_report(void)
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_MORSE_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_MORSE_ENABLED
|
||||
#define HAL_SIM_MORSE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_MORSE_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include "SIM_Aircraft.h"
|
||||
|
||||
@ -154,3 +162,6 @@ private:
|
||||
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
|
||||
#endif // HAL_SIM_MORSE_ENABLED
|
||||
|
@ -21,6 +21,12 @@
|
||||
|
||||
#include "SIM_SerialProximitySensor.h"
|
||||
|
||||
#ifndef HAL_SIM_PS_LIGHTWARE_ENABLED
|
||||
#define HAL_SIM_PS_LIGHTWARE_ENABLED HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_PS_LIGHTWARE_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
namespace SITL {
|
||||
@ -35,3 +41,5 @@ private:
|
||||
};
|
||||
|
||||
};
|
||||
|
||||
#endif // HAL_SIM_PS_LIGHTWARE_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_PS_LightWare_SF45B.h"
|
||||
|
||||
#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
@ -220,3 +222,5 @@ void PS_LightWare_SF45B::update_output_scan(const Location &location)
|
||||
send((char*)&packed_distance_data, sizeof(packed_distance_data));
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED
|
||||
|
@ -43,6 +43,12 @@ rc 2 1450
|
||||
|
||||
#include "SIM_PS_LightWare.h"
|
||||
|
||||
#ifndef HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED
|
||||
#define HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED HAL_SIM_PS_LIGHTWARE_ENABLED
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED
|
||||
|
||||
#include <AP_Math/crc.h>
|
||||
#include <AP_InternalError/AP_InternalError.h>
|
||||
|
||||
@ -258,3 +264,5 @@ private:
|
||||
};
|
||||
|
||||
};
|
||||
|
||||
#endif // HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_PS_RPLidarA2.h"
|
||||
|
||||
#if HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
@ -229,3 +231,5 @@ void PS_RPLidarA2::send_response_descriptor(uint32_t data_response_length, SendM
|
||||
abort();
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
|
@ -45,6 +45,12 @@ rc 2 1450
|
||||
|
||||
#include "SIM_SerialProximitySensor.h"
|
||||
|
||||
#ifndef HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
#define HAL_SIM_PS_RPLIDARA2_ENABLED HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
namespace SITL {
|
||||
@ -127,3 +133,5 @@ private:
|
||||
};
|
||||
|
||||
};
|
||||
|
||||
#endif // HAL_SIM_PS_RPLIDARA2_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_PS_TeraRangerTower.h"
|
||||
|
||||
#if HAL_SIM_PS_TERARANGERTOWER_ENABLED
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
#include <stdio.h>
|
||||
@ -75,3 +77,5 @@ void PS_TeraRangerTower::update(const Location &location)
|
||||
{
|
||||
update_output(location);
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_PS_TERARANGERTOWER_ENABLED
|
||||
|
@ -43,6 +43,12 @@ rc 2 1450
|
||||
|
||||
#include "SIM_SerialProximitySensor.h"
|
||||
|
||||
#ifndef HAL_SIM_PS_TERARANGERTOWER_ENABLED
|
||||
#define HAL_SIM_PS_TERARANGERTOWER_ENABLED HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_PS_TERARANGERTOWER_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
namespace SITL {
|
||||
@ -65,3 +71,5 @@ private:
|
||||
};
|
||||
|
||||
};
|
||||
|
||||
#endif // HAL_SIM_PS_TERARANGERTOWER_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_Scrimmage.h"
|
||||
|
||||
#if HAL_SIM_SCRIMMAGE_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <inttypes.h>
|
||||
#include <sys/stat.h>
|
||||
@ -130,3 +132,5 @@ void Scrimmage::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_SCRIMMAGE_ENABLED
|
||||
#define HAL_SIM_SCRIMMAGE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_SCRIMMAGE_ENABLED
|
||||
|
||||
#include <string>
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
@ -83,3 +91,5 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_SCRIMMAGE_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_SerialProximitySensor.h"
|
||||
|
||||
#if HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include <stdio.h>
|
||||
@ -134,3 +136,5 @@ float SerialProximitySensor::measure_distance_at_angle_bf(const Location &locati
|
||||
// ::fprintf(stderr, "Distance @%f = %fm\n", angle, min_dist_cm/100.0f);
|
||||
return min_dist_cm / 100.0f;
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED
|
||||
#define HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_SERIALPROXIMITYSENSOR_ENABLED
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
|
||||
#include <SITL/SITL.h>
|
||||
@ -56,3 +64,5 @@ private:
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_SilentWings.h"
|
||||
|
||||
#if HAL_SIM_SILENTWINGS_ENABLED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
|
||||
@ -318,3 +320,5 @@ void SilentWings::update(const struct sitl_input &input)
|
||||
report.frame_count = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_SILENTWINGS_ENABLED
|
||||
|
@ -15,6 +15,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_SILENTWINGS_ENABLED
|
||||
#define HAL_SIM_SILENTWINGS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_SILENTWINGS_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -110,3 +118,5 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_SILENTWINGS_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_Webots.h"
|
||||
|
||||
#if HAL_SIM_WEBOTS_ENABLED
|
||||
|
||||
#include <arpa/inet.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
@ -567,3 +569,5 @@ void Webots::report_FPS(void)
|
||||
// last_frame_count_s = state.timestamp;
|
||||
// }
|
||||
}
|
||||
|
||||
#endif // HAL_SIM_WEBOTS_ENABLED
|
||||
|
@ -17,6 +17,15 @@
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_WEBOTS_ENABLED
|
||||
#define HAL_SIM_WEBOTS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_WEBOTS_ENABLED
|
||||
|
||||
#include <cmath>
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -135,3 +144,5 @@ private:
|
||||
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_WEBOTS_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_XPlane.h"
|
||||
|
||||
#if HAL_SIM_XPLANE_ENABLED
|
||||
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <stdio.h>
|
||||
@ -488,3 +490,5 @@ void XPlane::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_XPLANE_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_XPLANE_ENABLED
|
||||
#define HAL_SIM_XPLANE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_XPLANE_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -112,3 +120,6 @@ private:
|
||||
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
|
||||
#endif // HAL_SIM_XPLANE_ENABLED
|
||||
|
@ -18,6 +18,8 @@
|
||||
|
||||
#include "SIM_last_letter.h"
|
||||
|
||||
#if HAL_SIM_LAST_LETTER_ENABLED
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <stdio.h>
|
||||
#include <sys/stat.h>
|
||||
@ -135,3 +137,5 @@ void last_letter::update(const struct sitl_input &input)
|
||||
}
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_LAST_LETTER_ENABLED
|
||||
|
@ -18,6 +18,14 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#ifndef HAL_SIM_LAST_LETTER_ENABLED
|
||||
#define HAL_SIM_LAST_LETTER_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
||||
#endif
|
||||
|
||||
#if HAL_SIM_LAST_LETTER_ENABLED
|
||||
|
||||
#include <AP_HAL/utility/Socket.h>
|
||||
|
||||
#include "SIM_Aircraft.h"
|
||||
@ -73,3 +81,5 @@ private:
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
||||
#endif // HAL_SIM_LAST_LETTER_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user