diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 29619f3e9d..668a36429a 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -135,7 +135,7 @@ void AC_PrecLand::calc_angles_and_pos(float alt_above_terrain_cm) return; } - // get body-frame angles to target from backend + // get angles to target from backend if (!_backend->get_angle_to_target(_angle_to_target.x, _angle_to_target.y)) { _have_estimate = false; return; diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 17cd41b8c0..4650928831 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -72,7 +72,7 @@ public: private: // calc_angles_and_pos - converts sensor's body-frame angles to earth-frame angles and position estimate - // body-frame angles stored in _bf_angle_to_target + // angles stored in _angle_to_target // earth-frame angles stored in _ef_angle_to_target // position estimate is stored in _target_pos void calc_angles_and_pos(float alt_above_terrain_cm); diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index 5c5ffdfc7d..6fc5559480 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -29,10 +29,10 @@ public: // what frame of reference is our sensor reporting in? virtual MAV_FRAME get_frame_of_reference(); - // get_angle_to_target - returns body frame angles (in radians) to target + // get_angle_to_target - returns angles (in radians) to target // returns true if angles are available, false if not (i.e. no target) - // x_angle_rad : body-frame roll direction, positive = target is to right (looking down) - // y_angle_rad : body-frame pitch direction, postiive = target is forward (looking down) + // x_angle_rad : roll direction, positive = target is to right (looking down) + // y_angle_rad : pitch direction, postiive = target is forward (looking down) virtual bool get_angle_to_target(float &x_angle_rad, float &y_angle_rad) = 0; // handle_msg - parses a mavlink message from the companion computer diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index 8b91488188..2f2142ab67 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -32,10 +32,10 @@ MAV_FRAME AC_PrecLand_Companion::get_frame_of_reference() return _frame; } -// get_angle_to_target - returns body frame angles (in radians) to target +// get_angle_to_target - returns angles (in radians) to target // returns true if angles are available, false if not (i.e. no target) -// x_angle_rad : body-frame roll direction, positive = target is to right (looking down) -// y_angle_rad : body-frame pitch direction, postiive = target is forward (looking down) +// x_angle_rad : roll direction, positive = target is to right (looking down) +// y_angle_rad : pitch direction, postiive = target is forward (looking down) bool AC_PrecLand_Companion::get_angle_to_target(float &x_angle_rad, float &y_angle_rad) { if (_new_estimate){ diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index a7c56a0c3e..4949d9bd91 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -27,10 +27,10 @@ public: // what frame of reference is our sensor reporting in? MAV_FRAME get_frame_of_reference(); - // get_angle_to_target - returns body frame angles (in radians) to target + // get_angle_to_target - returns angles (in radians) to target // returns true if angles are available, false if not (i.e. no target) - // x_angle_rad : body-frame roll direction, positive = target is to right (looking down) - // y_angle_rad : body-frame pitch direction, postiive = target is forward (looking down) + // x_angle_rad : roll direction, positive = target is to right (looking down) + // y_angle_rad : pitch direction, postiive = target is forward (looking down) bool get_angle_to_target(float &x_angle_rad, float &y_angle_rad); // handle_msg - parses a mavlink message from the companion computer @@ -40,7 +40,7 @@ private: // output from camera MAV_FRAME _frame; // what frame of reference is our sensor reporting in? - Vector2f _angle_to_target; // last body-frame angle to target + Vector2f _angle_to_target; // last angle to target float _distance_to_target; // distance from the camera to target in meters uint64_t _timestamp_us; // timestamp when the image was captured(synced via UAVCAN) bool _new_estimate; // true if new data from the camera has been received