Browse Source

SITL: remove set_yaw_degrees()

That function isn't being used anywhere.
master
Gustavo Jose de Sousa 9 years ago committed by Andrew Tridgell
parent
commit
ce8766e1cd
  1. 12
      libraries/SITL/SIM_Aircraft.cpp
  2. 3
      libraries/SITL/SIM_Aircraft.h

12
libraries/SITL/SIM_Aircraft.cpp

@ -142,18 +142,6 @@ void Aircraft::update_position(void) @@ -142,18 +142,6 @@ void Aircraft::update_position(void)
}
}
/*
rotate to the given yaw
*/
void Aircraft::set_yaw_degrees(float yaw_degrees)
{
float roll, pitch, yaw;
dcm.to_euler(&roll, &pitch, &yaw);
yaw = radians(yaw_degrees);
dcm.from_euler(roll, pitch, yaw);
}
/* advance time by deltat in seconds */
void Aircraft::time_advance(float deltat)
{

3
libraries/SITL/SIM_Aircraft.h

@ -142,9 +142,6 @@ protected: @@ -142,9 +142,6 @@ protected:
/* update location from position */
void update_position(void);
/* rotate to the given yaw */
void set_yaw_degrees(float yaw_degrees);
/* advance time by deltat in seconds */
void time_advance(float deltat);

Loading…
Cancel
Save