Browse Source

Sub: Remove two unused functions

mission-4.1.18
Jacob Walser 8 years ago
parent
commit
1ee1c01e43
  1. 2
      ArduSub/Sub.h
  2. 14
      ArduSub/position_vector.cpp

2
ArduSub/Sub.h

@ -651,10 +651,8 @@ private: @@ -651,10 +651,8 @@ private:
uint32_t perf_info_get_num_dropped();
Vector3f pv_location_to_vector(const Location& loc);
float pv_alt_above_origin(float alt_above_home_cm);
float pv_alt_above_home(float alt_above_origin_cm);
float pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination);
float pv_get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination);
float pv_distance_to_home_cm(const Vector3f &destination);
void init_rc_in();
void init_rc_out();
void enable_motor_output();

14
ArduSub/position_vector.cpp

@ -22,13 +22,6 @@ float Sub::pv_alt_above_origin(float alt_above_home_cm) @@ -22,13 +22,6 @@ float Sub::pv_alt_above_origin(float alt_above_home_cm)
return alt_above_home_cm + (ahrs.get_home().alt - origin.alt);
}
// pv_alt_above_home - convert altitude above EKF origin to altitude above home
float Sub::pv_alt_above_home(float alt_above_origin_cm)
{
const struct Location &origin = inertial_nav.get_origin();
return alt_above_origin_cm + (origin.alt - ahrs.get_home().alt);
}
// pv_get_bearing_cd - return bearing in centi-degrees between two positions
float Sub::pv_get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
{
@ -44,10 +37,3 @@ float Sub::pv_get_horizontal_distance_cm(const Vector3f &origin, const Vector3f @@ -44,10 +37,3 @@ float Sub::pv_get_horizontal_distance_cm(const Vector3f &origin, const Vector3f
{
return norm(destination.x-origin.x,destination.y-origin.y);
}
// returns distance between a destination and home in cm
float Sub::pv_distance_to_home_cm(const Vector3f &destination)
{
Vector3f home = pv_location_to_vector(ahrs.get_home());
return pv_get_horizontal_distance_cm(home, destination);
}

Loading…
Cancel
Save