mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
SITL: expose home yaw to FDMs
This commit is contained in:
parent
630d4410d4
commit
d425965f6d
@ -55,13 +55,11 @@ Aircraft::Aircraft(const char *home_str, const char *frame_str) :
|
||||
min_sleep_time(5000)
|
||||
#endif
|
||||
{
|
||||
float yaw_degrees;
|
||||
|
||||
parse_home(home_str, home, yaw_degrees);
|
||||
parse_home(home_str, home, home_yaw);
|
||||
location = home;
|
||||
ground_level = home.alt*0.01;
|
||||
|
||||
dcm.from_euler(0, 0, radians(yaw_degrees));
|
||||
dcm.from_euler(0, 0, radians(home_yaw));
|
||||
|
||||
set_speedup(1);
|
||||
|
||||
|
@ -98,6 +98,7 @@ protected:
|
||||
Location location;
|
||||
|
||||
float ground_level;
|
||||
float home_yaw;
|
||||
float frame_height;
|
||||
Matrix3f dcm; // rotation matrix, APM conventions, from body to earth
|
||||
Vector3f gyro; // rad/s
|
||||
|
Loading…
Reference in New Issue
Block a user