mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: Remove unused variables
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
7aeeb61f69
commit
2ba6f64281
@ -26,9 +26,7 @@ namespace SITL {
|
||||
BalanceBot::BalanceBot(const char *home_str, const char *frame_str) :
|
||||
Aircraft(home_str, frame_str),
|
||||
max_speed(4),
|
||||
max_accel(14),
|
||||
skid_turn_rate(140), // degrees/sec
|
||||
skid_steering(true)
|
||||
skid_turn_rate(140) // degrees/sec
|
||||
{
|
||||
dcm.from_euler(0,0,0); // initial yaw, pitch and roll in radians
|
||||
printf("Balance Bot Simulation Started\n");
|
||||
|
@ -39,9 +39,7 @@ private:
|
||||
float velocity_vf_x;
|
||||
|
||||
float max_speed;
|
||||
float max_accel;
|
||||
float skid_turn_rate;
|
||||
bool skid_steering;
|
||||
|
||||
float calc_yaw_rate(float steering);
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user