Setup basic scene to move the cube to last data received
This commit is contained in:
parent
73fed102c2
commit
372468b5a1
6 changed files with 59 additions and 4 deletions
|
|
@ -6,8 +6,10 @@
|
|||
#include "godot_cpp/core/math.hpp"
|
||||
#include "godot_cpp/core/memory.hpp"
|
||||
#include "godot_cpp/core/print_string.hpp"
|
||||
#include "godot_cpp/variant/basis.hpp"
|
||||
#include "godot_cpp/variant/packed_byte_array.hpp"
|
||||
#include "godot_cpp/variant/quaternion.hpp"
|
||||
#include "godot_cpp/variant/transform3d.hpp"
|
||||
#include "godot_cpp/variant/vector3.hpp"
|
||||
#include "mavlink/all/mavlink.h" // IWYU pragma: keep; always include the mavlink.h file for selected dialect
|
||||
#include "mavlink/common/mavlink_msg_sim_state.h"
|
||||
|
|
@ -21,6 +23,7 @@ using namespace godot;
|
|||
void MarshConnector::_bind_methods() {
|
||||
ClassDB::bind_method(D_METHOD("send_heartbeat"),
|
||||
&MarshConnector::send_heartbeat);
|
||||
ClassDB::bind_method(D_METHOD("get_aircraft"), &MarshConnector::get_aircraft);
|
||||
}
|
||||
|
||||
MarshConnector::MarshConnector() {
|
||||
|
|
@ -123,14 +126,18 @@ float MarshConnector::get_parameter(const String &id) {
|
|||
return Math_NAN;
|
||||
}
|
||||
|
||||
Transform3D MarshConnector::get_aircraft() {
|
||||
return Transform3D{Basis{last_rotation}, last_location};
|
||||
}
|
||||
|
||||
Vector2 MarshConnector::local_meters_from_global_degrees(double latitude,
|
||||
double longitude) {
|
||||
|
||||
// Convert everything to radians
|
||||
const double lat = latitude * Math_PI / 180.0;
|
||||
const double lon = longitude * Math_PI / 180.0;
|
||||
const double lat0 = parameters[LOCAL_FRAME_LAT] * M_PI / 180.0;
|
||||
const double lon0 = parameters[LOCAL_FRAME_LON] * M_PI / 180.0;
|
||||
const double lat0 = parameters[LOCAL_FRAME_LAT] * Math_PI / 180.0;
|
||||
const double lon0 = parameters[LOCAL_FRAME_LON] * Math_PI / 180.0;
|
||||
|
||||
double EARTH_RADIUS = 6371008.7714; // mean radius for WGS-84, in meters
|
||||
|
||||
|
|
|
|||
|
|
@ -5,6 +5,7 @@
|
|||
#include "godot_cpp/classes/packet_peer_udp.hpp"
|
||||
#include "godot_cpp/classes/timer.hpp"
|
||||
#include "godot_cpp/variant/quaternion.hpp"
|
||||
#include "godot_cpp/variant/transform3d.hpp"
|
||||
#include "godot_cpp/variant/vector2.hpp"
|
||||
#include "godot_cpp/variant/vector3.hpp"
|
||||
#include "mavlink/mavlink_types.h"
|
||||
|
|
@ -32,6 +33,8 @@ public:
|
|||
Error set_parameter(const String &id, float value);
|
||||
// Get current parameter value
|
||||
float get_parameter(const String &id);
|
||||
// Get current state of the aircraft
|
||||
Transform3D get_aircraft();
|
||||
|
||||
// Convert from global coordinates to local position x=north, y=east
|
||||
// taking into account current configuration.
|
||||
|
|
|
|||
Loading…
Add table
Add a link
Reference in a new issue