AC_PrecLand: update comments to reflect change from bf_angle to angle

This commit is contained in:
squilter 2015-10-23 13:04:40 -04:00 committed by Randy Mackay
parent 9e7099f5ee
commit 9de2ec04f6
5 changed files with 12 additions and 12 deletions

View File

@ -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;

View File

@ -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);

View File

@ -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

View File

@ -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){

View File

@ -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