diff --git a/libraries/SITL/SIM_Rover.cpp b/libraries/SITL/SIM_Rover.cpp index 17833580cd..2a3f42fd83 100644 --- a/libraries/SITL/SIM_Rover.cpp +++ b/libraries/SITL/SIM_Rover.cpp @@ -26,7 +26,7 @@ /* constructor */ -Rover::Rover(const char *home_str, const char *frame_str) : +SimRover::SimRover(const char *home_str, const char *frame_str) : Aircraft(home_str, frame_str), max_speed(20), max_accel(30), @@ -52,7 +52,7 @@ Rover::Rover(const char *home_str, const char *frame_str) : /* return turning circle (diameter) in meters for steering angle proportion in degrees */ -float Rover::turn_circle(float steering) +float SimRover::turn_circle(float steering) { if (fabsf(steering) < 1.0e-6) { return 0; @@ -63,7 +63,7 @@ float Rover::turn_circle(float steering) /* return yaw rate in degrees/second given steering_angle and speed */ -float Rover::calc_yaw_rate(float steering, float speed) +float SimRover::calc_yaw_rate(float steering, float speed) { if (skid_steering) { return steering * skid_turn_rate; @@ -81,7 +81,7 @@ float Rover::calc_yaw_rate(float steering, float speed) /* return lateral acceleration in m/s/s */ -float Rover::calc_lat_accel(float steering_angle, float speed) +float SimRover::calc_lat_accel(float steering_angle, float speed) { float yaw_rate = calc_yaw_rate(steering_angle, speed); float accel = radians(yaw_rate) * speed; @@ -91,7 +91,7 @@ float Rover::calc_lat_accel(float steering_angle, float speed) /* update the rover simulation by one time step */ -void Rover::update(const struct sitl_input &input) +void SimRover::update(const struct sitl_input &input) { float steering, throttle; diff --git a/libraries/SITL/SIM_Rover.h b/libraries/SITL/SIM_Rover.h index 2234736823..6dd6e1ed36 100644 --- a/libraries/SITL/SIM_Rover.h +++ b/libraries/SITL/SIM_Rover.h @@ -25,17 +25,17 @@ /* a rover simulator */ -class Rover : public Aircraft +class SimRover : public Aircraft { public: - Rover(const char *home_str, const char *frame_str); + SimRover(const char *home_str, const char *frame_str); /* update model by one time step */ void update(const struct sitl_input &input); /* static object creator */ static Aircraft *create(const char *home_str, const char *frame_str) { - return new Rover(home_str, frame_str); + return new SimRover(home_str, frame_str); } private: