|
Spacecraft Control Framework 1.0
Spacecraft Control Library
|
Coordinate transformation functions. More...
Go to the source code of this file.
Classes | |
| struct | sun_vector_out_s |
Typedefs | |
| typedef struct sun_vector_out_s | sun_vector_out |
Functions | |
| ml_matrix | az_el_range_range_rate_to_rv (const ml_matrix &q_radar_to_hills, double az, double el, double range, double range_dot) |
| Converts az, el, range and range rate to exact r and approximate v. More... | |
| ml_matrix | q_from_u (const ml_matrix &u_catalog, const ml_matrix &u_meas) |
| Returns a quaternion given at least 3 matching vectors. More... | |
| double | q_to_angle (const ml_matrix &quaternion) |
| Returns value of the angle from the quaternion in radians. More... | |
| ml_matrix | q_to_vec (const ml_matrix &quaternion) |
| Returns the value of the vector from quaternion. More... | |
| ml_matrix | au_to_q (double angle, double unit_vec[3]) |
| Compute quaternion from angle and unit vector, array format. More... | |
| ml_matrix | au_to_q (double angle, const ml_matrix &unit_vec) |
| Compute quaternion from angle and unit vector, matrix format. More... | |
| double | q_to_au (const ml_matrix &quaternion, ml_matrix &unit_vec) |
| Compute angle and unit vector from quaternion. More... | |
| ml_matrix | eul_to_mat (const ml_matrix &euler) |
| Convert 3-2-1 Euler angle sequence to a matrix that transforms in the direction of the rotation. More... | |
| ml_matrix | eul_to_q (const ml_matrix &euler) |
| Convert 3-2-1 Euler angle sequence to a quaternion that transforms in the direction of the rotation. | |
| ml_matrix | delta_eul_to_q (const ml_matrix &q, const ml_matrix &euler) |
| Apply a 3-2-1 Euler angle sequence to a quaternion that transforms in the direction of the rotation. More... | |
| ml_matrix | rot_mat_x (const double &a) |
| Generate a rotation matrix for angular rotation about the x axis. More... | |
| ml_matrix | rot_mat_y (const double &a) |
| Generate a rotation matrix for angular rotation about the y axis. More... | |
| ml_matrix | rot_mat_z (const double &a) |
| Generate a rotation matrix for angular rotation about the z axis. More... | |
| ml_matrix | mat_to_q (const ml_matrix &mat) |
| Convert a matrix to a quaternion. More... | |
| ml_matrix | mat_to_eul (const ml_matrix &mat, const ml_matrix &euler) |
| Convert a matrix to an Euler angle sequence. More... | |
| ml_matrix | u_to_q (const ml_matrix &vec1, const ml_matrix &vec2) |
| Computes the quaternion which aligns one vector with a second. More... | |
| ml_matrix | perpendicular (const ml_matrix &vec) |
| Computes the perpendicular vector. More... | |
| ml_matrix | q_error (const ml_matrix &q_ref, const ml_matrix &q_meas) |
| Finds the small error between two quaternions and converts them into an angle vector. More... | |
| ml_matrix | qb_to_i_dot (const ml_matrix &quaternion, const ml_matrix &w) |
| Calculates the derivative of the body to inertial quaternion. More... | |
| ml_matrix | qi_to_b_dot (const ml_matrix &quat, const ml_matrix &w) |
| Calculates the derivative of the inertial to body quaternion. More... | |
| ml_matrix | qeb_re_ub_to_az_el (const ml_matrix &qEB, const ml_matrix &rE, const ml_matrix &vB) |
| Calculate azimuth & elevation angle from ECI to body quaternion, position, and boresight vector. More... | |
| ml_matrix | mat_eci_to_lvlh (const ml_matrix &pos, const ml_matrix &vel) |
| Generate the matrix that transforms from ECI to LVLH coordinates. More... | |
| ml_matrix | q_eci_to_lvlh (const ml_matrix &pos, const ml_matrix &vel) |
| Generate the quaternion that transforms from ECI to LVLH coordinates. More... | |
| ml_matrix | mat_eci_to_hills (const ml_matrix &r, const ml_matrix &v) |
| Generate the matrix that transforms from ECI to Hills coordinates. More... | |
| ml_matrix | q_eci_to_hills (const ml_matrix &r, const ml_matrix &v) |
| Generate the quaternion that transforms from ECI to Hills coordinates. More... | |
| ml_matrix | eci_to_hills (const ml_matrix &x0, const ml_matrix &x1) |
| Transform from two ECI states to one relative state in Hills-frame. More... | |
| ml_matrix | hills_to_eci (const ml_matrix &x0, const ml_matrix &xH) |
| Transform from a relative state in Hills-frame to an absolute ECI state. More... | |
| ml_matrix | qslerp (const ml_matrix &quat1, const ml_matrix &quat2, double t) |
| Interpolates between two quaternions. More... | |
| ml_matrix | lat_lon_alt_to_pos (double lat, double lon, double h, double f=FLATTENING_FACTOR, double a=RADIUS_EARTH) |
| Compute EF position vector from latitude, longitude, and altitude. More... | |
| ml_matrix | lat_lon_alt_to_pos (const ml_matrix &lat_lon_alt, double f=FLATTENING_FACTOR, double a=RADIUS_EARTH) |
| Compute EF position vector from matrix [latitude;longitude;altitude]. More... | |
| ml_matrix | lat_lon_to_pos (double lat, double lon, double f, double a, bool is_geodetic) |
| Converts latitude and longitude to r for an ellipsoidal planet. More... | |
| ml_matrix | lat_lon_to_pos (double lat, double lon, double f=FLATTENING_FACTOR, double a=RADIUS_EARTH, int type=0) |
| Converts latitude and longitude to r for an ellipsoidal planet. More... | |
| ml_matrix | pos_to_lat_lon_alt (const ml_matrix &efPos, double f=FLATTENING_FACTOR, double a=RADIUS_EARTH, double tolerance=1.0e-6) |
| Compute latitude, longitude, and altitude from EF position vector. More... | |
| void | cart_to_sph (const ml_matrix &x, const ml_matrix &y, const ml_matrix &z, ml_matrix &r, ml_matrix &theta, ml_matrix &phi) |
| Converts cartesian coordinates to spherical. More... | |
| ml_matrix | cart_to_sph (const ml_matrix &x) |
| Converts cartesian coordinates to spherical. Stacked form. More... | |
| void | sph_to_cart (const ml_matrix &r, const ml_matrix &theta, const ml_matrix &phi, ml_matrix &x, ml_matrix &y, ml_matrix &z) |
| Convert spherical coordinates to cartesian. More... | |
| ml_matrix | RPhiTheta2Cart (const ml_matrix &r) |
| Computes the transformation matrix from an r, phi, theta frame to cartesian. More... | |
| ml_matrix | CameraToECI (double az, double el, double tt, const ml_matrix &qECIToBody, const ml_matrix &mBaseToBody) |
| Computes the transformation matrix from a camera frame with 3 rotations to the body frame. More... | |
| ml_matrix | eci_to_ned (const ml_matrix &r, int opt=0, double f=FLATTENING_FACTOR) |
| Computes the transformation matrix or quaternion from a eciframe to the North East Down (NED) frame. More... | |
| ml_matrix | u_to_az_el (const ml_matrix &u) |
| Computes the azimuth and elevation of a unit vector. More... | |
| ml_matrix | u_to_x_z (const ml_matrix &u) |
| Computes the x and z rotations to align z with a unit vector. More... | |
| ml_matrix | az_el_to_u (double az, double el) |
| Computes u from azimuth and elevation of a unit vector. More... | |
| ml_matrix | az_el_to_u (const ml_matrix &az, const ml_matrix &el) |
| Compute a unit vector from azimuth and elevation. More... | |
| ml_matrix | q_from_dq (const ml_matrix &q, const ml_matrix &dX) |
| Computes q as the product of q and a delta quaternion. More... | |
| ml_matrix | dq_from_dX (const ml_matrix &dX) |
| Delta quaternion from a 3 vector. More... | |
| ml_matrix | r_lvlh_to_eci (const ml_matrix &r_eci, const ml_matrix &v_eci, const ml_matrix &r) |
| LVLH position to ECI. More... | |
| ml_matrix | v_lvlh_to_eci (const ml_matrix &r_eci, const ml_matrix &v_eci, const ml_matrix &v) |
| ECI position to LVLH. More... | |
| ml_matrix | r_eci_to_lvlh (const ml_matrix &r_eci, const ml_matrix &v_eci, const ml_matrix &r) |
| LVLH position to ECI. More... | |
| ml_matrix | v_eci_to_lvlh (const ml_matrix &r_eci, const ml_matrix &v_eci, const ml_matrix &v) |
| ECI position to LVLH. More... | |
| ml_matrix | x_lvlh_to_eci (const ml_matrix &r_eci, const ml_matrix &v_eci, const ml_matrix &x) |
| LVLH state to ECI. More... | |
| ml_matrix | x_eci_to_lvlh (const ml_matrix &r_eci, const ml_matrix &v_eci, const ml_matrix &x) |
| ECI state to LVLH. More... | |
| ml_matrix | x_lvlh_to_eci (const ml_matrix &x_eci, const ml_matrix &x) |
| ECI state to LVLH. More... | |
| ml_matrix | x_eci_to_lvlh (const ml_matrix &x_eci, const ml_matrix &x) |
| ECI state to LVLH. More... | |
| ml_matrix | LLAToECEF (const ml_matrix &lla, double rP=RADIUS_EARTH) |
| Compute ECEF position from latitude, longitude, altitude. More... | |
| ml_matrix | small_angles_to_q (const ml_matrix &angle) |
| Convert small angles to a quaternion. More... | |
| ml_matrix | spice_to_3_by_3 (const ml_matrix &m, int k=1) |
| Convert SPICE rotation matrix to 3x3. More... | |
| double | esd_to_azim (const ml_matrix &u) |
| Convert an East-South-Down vector to azimuth from North. More... | |
| double | esd_to_elev (const ml_matrix &u) |
| Convert an East-South-Down vector to elevation from nadir. More... | |
| ml_matrix | azim_elev_to_esd (const double &azim, const double &elev) |
| Convert azimuth / elevation angles to an East-South-Down unit vector. More... | |
| ml_matrix | ecef_to_esd (const ml_matrix &rEF) |
| Compute rotation matrix from Earth-fixed frame to East-South-Down frame at given Earth-fixed position. More... | |
| ml_matrix | u_eci_to_az_el_body (const ml_matrix &u_eci, const ml_matrix &q_eci_to_body, const ml_matrix &q_body_to_base) |
| Find az and el from an ECI vector. More... | |
| sun_vector_out | sun_vector_pointing (const ml_matrix &u_eci, const ml_matrix &u_sun_eci) |
| Rotation angles to point a solar wing at the sun. More... | |
| ml_matrix | target_from_r_v_d (const ml_matrix &r, double rP, const ml_matrix &v, double d) |
| Landing target. More... | |
| ml_matrix | ef_to_lla (const ml_matrix &r) |
| EF to LLA. | |
| ml_matrix | eci_to_llr (const ml_matrix &eciCoord, double jd) |
| EF to LLA. | |
| ml_matrix | q_from_two_u (const ml_matrix &u, const ml_matrix &v) |
| Quaternion from two unit vectors. | |
| ml_matrix | q_to_ra_dec (const ml_matrix &quaternion, const ml_matrix &uu) |
| Compute right ascension and declination (in radians) of a unit vector in the body frame from a quaterion that transforms from the inertial to the body frame. More... | |
| ml_matrix | u_to_ra_dec (const ml_matrix &unit_vec) |
| Computes right ascension and declination from a unit vector. More... | |
| ml_matrix | u_to_ra_dec (const ml_matrix &unit_vec, bool normalize) |
| Computes right ascension and declination from a unit vector and normalizes the result. More... | |
| ml_matrix | ra_dec_to_q (const ml_matrix &uu, double ra, double dec) |
| Compute a quaternion from right ascension and declination. More... | |
| ml_matrix | ra_dec_to_u (double ra, double dec) |
| Calculate a unit vector from right ascension and declination. More... | |
| ml_matrix | ra_dec_to_u (const ml_matrix &ra, const ml_matrix &dec) |
| Calculate a unit vector from right ascension and declination. More... | |
| ml_matrix | az_el_to_q (ml_matrix az, ml_matrix el) |
| Compute a quaternion from azimuth and elevation. More... | |
| ml_matrix | az_el_to_q (double az, double el) |
| Compute a quaternion from azimuth and elevation. More... | |
Coordinate transformation functions.
| ml_matrix az_el_range_range_rate_to_rv | ( | const ml_matrix & | q_radar_to_hills, |
| double | az, | ||
| double | el, | ||
| double | range, | ||
| double | range_dot | ||
| ) |
Converts az, el, range and range rate to exact r and approximate v.
| az | Azimuth |
| el | Elevation |
| range | Range |
| range_dot | Range rate |
References pinv().
| ml_matrix q_from_u | ( | const ml_matrix & | u_catalog, |
| const ml_matrix & | u_meas | ||
| ) |
Returns a quaternion given at least 3 matching vectors.
| u_catalog | A 3xn matrix of catalog unit vectors |
| u_meas | A 3xn matrix of measured unit vectors |
References mat_to_q(), orthogonalize(), and pinv().
| double q_to_angle | ( | const ml_matrix & | quaternion | ) |
Returns value of the angle from the quaternion in radians.
| quaternion | The quaternion. |
Referenced by q_to_au(), and PID3Axis::Update().
| ml_matrix q_to_vec | ( | const ml_matrix & | quaternion | ) |
Returns the value of the vector from quaternion.
| quaternion | The quaternion. |
Referenced by q_to_au(), and PID3Axis::Update().
| ml_matrix au_to_q | ( | double | angle, |
| double | unit_vec[3] | ||
| ) |
Compute quaternion from angle and unit vector, array format.
| angle | |
| unit_vec |
Referenced by AlignThruster(), orbit_acquisition_dv(), PID3Axis::SetAlignAndRotateCommand(), multi_body_central_hub_with_rwa::state_derivative(), multi_body_central_hub::state_derivative(), target_from_r_v_d(), aero_newtonian::update(), and PID3Axis::Update().
| ml_matrix au_to_q | ( | double | angle, |
| const ml_matrix & | unit_vec | ||
| ) |
Compute quaternion from angle and unit vector, matrix format.
| angle | |
| unit_vec |
| double q_to_au | ( | const ml_matrix & | quaternion, |
| ml_matrix & | unit_vec | ||
| ) |
Compute angle and unit vector from quaternion.
| quaternion | The quaternion. |
| unit_vec | The unit vector will be returned in this matrix. |
References q_to_angle(), and q_to_vec().
| ml_matrix eul_to_mat | ( | const ml_matrix & | euler | ) |
Convert 3-2-1 Euler angle sequence to a matrix that transforms in the direction of the rotation.
| euler | (3,1) The Euler angle sequence to be converted. |
| ml_matrix delta_eul_to_q | ( | const ml_matrix & | q, |
| const ml_matrix & | euler | ||
| ) |
Apply a 3-2-1 Euler angle sequence to a quaternion that transforms in the direction of the rotation.
Apply a 3-2-1 Euler angle sequence to a quaternion that transforms in the direction of the rotation.
| euler | (3,1) The Euler angle sequence to be converted. |
| q | (4,1) The original quaternion. |
References eul_to_q().
| ml_matrix rot_mat_x | ( | const double & | a | ) |
Generate a rotation matrix for angular rotation about the x axis.
Generate a rotation matrix for angular rotation about the x axis.
| a | Angle of rotation (rad) |
| ml_matrix rot_mat_y | ( | const double & | a | ) |
Generate a rotation matrix for angular rotation about the y axis.
Generate a rotation matrix for angular rotation about the y axis.
| a | Angle of rotation (rad) |
| ml_matrix rot_mat_z | ( | const double & | a | ) |
Generate a rotation matrix for angular rotation about the z axis.
Generate a rotation matrix for angular rotation about the z axis.
| a | Angle of rotation (rad) |
| ml_matrix mat_to_q | ( | const ml_matrix & | mat | ) |
Convert a matrix to a quaternion.
Convert a matrix to a quaternion.
Wrapper for the MatrixLib function q_from_mat.
| mat | (3,3) The matrix to be converted. |
Referenced by az_el_to_q(), eci_to_ned(), q_eci_to_hills(), q_eci_to_lvlh(), q_from_u(), and sun_vector_pointing().
| ml_matrix mat_to_eul | ( | const ml_matrix & | mat, |
| const ml_matrix & | euler | ||
| ) |
Convert a matrix to an Euler angle sequence.
Wrapper for the MatrixLib function q_mat_to_eul.
| mat | (3,3) |
| euler | (3,1) |
| ml_matrix u_to_q | ( | const ml_matrix & | vec1, |
| const ml_matrix & | vec2 | ||
| ) |
Computes the quaternion which aligns one vector with a second.
Computes the quaternion which aligns one vector with a second.
This is not a unique solution.
Wrapper for the MatrixLib function q_from_u.
| vec1 | (3,1) Starting vector. |
| vec2 | (3,1) Ending vector. |
Referenced by AlignThruster(), sensor_cone(), PID3Axis::SetAlignAndRotateCommand(), sun_vector_pointing(), and PID3Axis::Update().
| ml_matrix perpendicular | ( | const ml_matrix & | vec | ) |
Computes the perpendicular vector.
Wrapper for the MatrixLib function q_perpendicular.
| vec | (3,1) The vector. |
Referenced by q_from_two_u().
| ml_matrix q_error | ( | const ml_matrix & | q_ref, |
| const ml_matrix & | q_meas | ||
| ) |
Finds the small error between two quaternions and converts them into an angle vector.
This routine gives the correct sign when both vectors transform from frame a to frame b and frame b is the body frame. If the convention is reversed you must reverse the sign.
| q_ref | (4,1) Reference quaternion. |
| q_meas | (4,1) Measured quaternion. |
| ml_matrix qb_to_i_dot | ( | const ml_matrix & | quaternion, |
| const ml_matrix & | w | ||
| ) |
Calculates the derivative of the body to inertial quaternion.
Calculates the derivative of the body to inertial quaternion.
| quaternion | (4,1) The quaternion, should be a column vector |
| w | (3,1) The anglular velocity, a 3 element column vector |
| ml_matrix qi_to_b_dot | ( | const ml_matrix & | quat, |
| const ml_matrix & | w | ||
| ) |
Calculates the derivative of the inertial to body quaternion.
Calculates the derivative of the inertial to body quaternion.
| quat | (4,1) The quaternion, should be a column vector. |
| w | (3,1) The angular rate, a 3 element column vector. |
Referenced by attitude_propagation(), multi_body_central_hub_with_rwa::state_derivative(), and multi_body_central_hub::state_derivative().
| ml_matrix qeb_re_ub_to_az_el | ( | const ml_matrix & | qEB, |
| const ml_matrix & | rE, | ||
| const ml_matrix & | vB | ||
| ) |
Calculate azimuth & elevation angle from ECI to body quaternion, position, and boresight vector.
Calculate azimuth & elevation angle from ECI to body quaternion, position, and boresight vector.
Azimuth angle is measured clockwise from north to the projection of the boresight vector onto the east-north plane. Elevation angle is the "angle off nadir", the angular distance between the nadir vector and the boresight vector. Adapted by KenW from Joe Mueller's QEB_RE_UB_to_AzEl.m matlab code in /Contracts/NavyReconfigure/Matlab
| qEB | (4,1) ECI to spacecraft body coordinate frame quaternion |
| rE | (3,1) ECI position of spacecraft |
| vB | (3,1) boresight vector defined in body frame |
| ml_matrix mat_eci_to_lvlh | ( | const ml_matrix & | pos, |
| const ml_matrix & | vel | ||
| ) |
Generate the matrix that transforms from ECI to LVLH coordinates.
For LVLH coordinates; z is in the -r direction y is in the - rxv direction x completes the set
| pos | (3,1) Position vectors |
| vel | (3,1) Velocity vectors |
Referenced by q_eci_to_lvlh().
| ml_matrix q_eci_to_lvlh | ( | const ml_matrix & | pos, |
| const ml_matrix & | vel | ||
| ) |
Generate the quaternion that transforms from ECI to LVLH coordinates.
| pos | (3,1) Position vector |
| vel | (3,1) Velocity vector |
References mat_eci_to_lvlh(), and mat_to_q().
Referenced by r_eci_to_lvlh(), r_lvlh_to_eci(), v_eci_to_lvlh(), v_lvlh_to_eci(), x_eci_to_lvlh(), and x_lvlh_to_eci().
| ml_matrix mat_eci_to_hills | ( | const ml_matrix & | r, |
| const ml_matrix & | v | ||
| ) |
Generate the matrix that transforms from ECI to Hills coordinates.
For Hills coordinates; x is in the + r direction z is in the + rxv direction y completes the set (aligned with velocity for circular orbits)
| r | (3,1) Position vector |
| v | (3,1) Velocity vector |
Referenced by eci_to_hills(), hills_to_eci(), and q_eci_to_hills().
| ml_matrix q_eci_to_hills | ( | const ml_matrix & | r, |
| const ml_matrix & | v | ||
| ) |
Generate the quaternion that transforms from ECI to Hills coordinates.
| r | (3,1) Position vector |
| v | (3,1) Velocity vector |
References mat_eci_to_hills(), and mat_to_q().
Referenced by AlignThruster().
| ml_matrix eci_to_hills | ( | const ml_matrix & | x0, |
| const ml_matrix & | x1 | ||
| ) |
Transform from two ECI states to one relative state in Hills-frame.
| x0 | (6,1) ECI position and velocity of reference orbit |
| x1 | (6,1) ECI position and velocity of secondary orbit |
References mat_eci_to_hills().
Referenced by FFEccDeltaElem2Hills().
| ml_matrix hills_to_eci | ( | const ml_matrix & | x0, |
| const ml_matrix & | xH | ||
| ) |
Transform from a relative state in Hills-frame to an absolute ECI state.
| x0 | (6,1) ECI position and velocity of reference orbit |
| xH | (6,1) Relative position and velocity in Hills-frame |
References mat_eci_to_hills().
Referenced by FFEccHills2DeltaElem().
| ml_matrix q_to_ra_dec | ( | const ml_matrix & | quaternion, |
| const ml_matrix & | uu | ||
| ) |
Compute right ascension and declination (in radians) of a unit vector in the body frame from a quaterion that transforms from the inertial to the body frame.
Compute right ascension and declination from a quaterion.
| quaternion | (4,1) The quaternion (inertial to body). |
| uu | (3,1) unit vector in the body frame. |
References u_to_ra_dec().
| ml_matrix u_to_ra_dec | ( | const ml_matrix & | unit_vec | ) |
Computes right ascension and declination from a unit vector.
Computes right ascension and declination from a unit vector.
| unit_vec | (3,n) Unit vector(s) |
Referenced by q_to_ra_dec().
| ml_matrix u_to_ra_dec | ( | const ml_matrix & | unit_vec, |
| bool | normalize | ||
| ) |
Computes right ascension and declination from a unit vector and normalizes the result.
Computes right ascension and declination from a unit vector and normalizes the result.
| unit_vec | (3,n) Unit vector(s) |
| normalize | Flag indicating whether the return vector should be normalized. |
References TWO_PI.
| ml_matrix ra_dec_to_q | ( | const ml_matrix & | uu, |
| double | ra, | ||
| double | dec | ||
| ) |
Compute a quaternion from right ascension and declination.
If right ascension and declination are defined in frame a, and u is fixed in frame b, q transforms from frame a to b such that u lies along the vector determined by (rA,dec) in frame a.
| uu | (3,1) unit vector |
| ra | (1) Right ascension [rad] |
| dec | (1) Declination [rad] |
References ra_dec_to_u().
| ml_matrix ra_dec_to_u | ( | double | ra, |
| double | dec | ||
| ) |
Calculate a unit vector from right ascension and declination.
| ra | (1) Right ascension [rad] |
| dec | (1) Declination [rad] |
Referenced by star::CalculateVector(), local_star_position(), ra_dec_to_q(), ra_dec_to_u(), stellar_reduction(), and star::UnitVector().
| ml_matrix ra_dec_to_u | ( | const ml_matrix & | ra, |
| const ml_matrix & | dec | ||
| ) |
Calculate a unit vector from right ascension and declination.
| ra | (1,n) Right ascension [rad] |
| dec | (1,n) Declination [rad] |
References ra_dec_to_u().
| ml_matrix az_el_to_q | ( | ml_matrix | az, |
| ml_matrix | el | ||
| ) |
Compute a quaternion from azimuth and elevation.
Compute a quaternion from azimuth and elevation.
| az | Is the azimuth (angle about +z from +x) |
| el | is the elevation (angle about +y from +x) |
References az_el_to_q().
Referenced by az_el_to_q().
| ml_matrix az_el_to_q | ( | double | az, |
| double | el | ||
| ) |
Compute a quaternion from azimuth and elevation.
Compute a quaternion from azimuth and elevation.
| az | Is the azimuth (angle about +z from +x) |
| el | is the elevation (angle about +y from +x) |
References mat_to_q().
| ml_matrix qslerp | ( | const ml_matrix & | quat1, |
| const ml_matrix & | quat2, | ||
| double | t | ||
| ) |
Interpolates between two quaternions.
| quat1 | (4,1) |
| quat2 | (4,1) |
| t | (1) between 0 to 1 |
| ml_matrix lat_lon_alt_to_pos | ( | double | lat, |
| double | lon, | ||
| double | h, | ||
| double | f, | ||
| double | a | ||
| ) |
Compute EF position vector from latitude, longitude, and altitude.
| lat | Latitude in radians. |
| lon | Longitude in radians. |
| h | Distance above the subsatellite point. |
| f | Flattening factor |
| a | Equatorial radius |
Referenced by earth_surface_ef_pos(), gps_eci_state_from_data(), and lat_lon_alt_to_pos().
| ml_matrix lat_lon_alt_to_pos | ( | const ml_matrix & | lat_lon_alt, |
| double | f, | ||
| double | a | ||
| ) |
Compute EF position vector from matrix [latitude;longitude;altitude].
Compute EF position vector from matrix [latitude;longitude;altitude].
| lat_lon_alt | [lat;lon;alt] |
| f | Flattening factor |
| a | Equatorial radius |
References lat_lon_alt_to_pos().
| ml_matrix lat_lon_to_pos | ( | double | lat, |
| double | lon, | ||
| double | f, | ||
| double | a, | ||
| bool | is_geodetic | ||
| ) |
Converts latitude and longitude to r for an ellipsoidal planet.
| lat | Latitude in radians. |
| lon | Longitude in radians. |
| f | Flattening factor |
| a | Equatorial radius |
| is_geodetic | true for geodetic |
| ml_matrix lat_lon_to_pos | ( | double | lat, |
| double | lon, | ||
| double | f, | ||
| double | a, | ||
| int | type | ||
| ) |
Converts latitude and longitude to r for an ellipsoidal planet.
| lat | Latitude in radians. |
| lon | Longitude in radians. |
| f | Flattening factor |
| a | Equatorial radius |
| type | 0 for Geodetic |
| ml_matrix pos_to_lat_lon_alt | ( | const ml_matrix & | efPos, |
| double | f, | ||
| double | a, | ||
| double | tolerance | ||
| ) |
Compute latitude, longitude, and altitude from EF position vector.
| efPos | ECEF position (km) |
| f | Flattening factor |
| a | Equatorial radius |
| tolerance | Tolerance for the iteration |
References PI.
Referenced by earth_surface_ef_pos(), and sc_earth_elevation::elevationForEFPos().
| void cart_to_sph | ( | const ml_matrix & | x, |
| const ml_matrix & | y, | ||
| const ml_matrix & | z, | ||
| ml_matrix & | r, | ||
| ml_matrix & | theta, | ||
| ml_matrix & | phi | ||
| ) |
Converts cartesian coordinates to spherical.
Individual vector form.
| x | |
| y | |
| z | |
| r | |
| theta | |
| phi |
Referenced by mag_field().
| ml_matrix cart_to_sph | ( | const ml_matrix & | x | ) |
Converts cartesian coordinates to spherical. Stacked form.
Converts cartesian coordinates to spherical. Stacked form.
Stacked matrix form.
| x | Position state [x;y;z] |
| void sph_to_cart | ( | const ml_matrix & | r, |
| const ml_matrix & | theta, | ||
| const ml_matrix & | phi, | ||
| ml_matrix & | x, | ||
| ml_matrix & | y, | ||
| ml_matrix & | z | ||
| ) |
Convert spherical coordinates to cartesian.
Convert spherical coordinates to cartesian.
Individual vector form.
| r | |
| theta | |
| phi | |
| x | |
| y | |
| z |
| ml_matrix RPhiTheta2Cart | ( | const ml_matrix & | r | ) |
Computes the transformation matrix from an r, phi, theta frame to cartesian.
Computes the transformation matrix from an r, phi, theta frame to cartesian.
In an RPT frame, r is the radial direction, phi is 'east', and theta is in the direction of co-elevation. When theta is zero the r vector is in the xy-plane.
| r | Position vector |
Referenced by mag_field().
| ml_matrix CameraToECI | ( | double | az, |
| double | el, | ||
| double | tt, | ||
| const ml_matrix & | qECIToBody, | ||
| const ml_matrix & | mBaseToBody | ||
| ) |
Computes the transformation matrix from a camera frame with 3 rotations to the body frame.
Computes the transformation matrix from a camera frame with 3 rotations to the body frame.
| az | Azimuth (rad) |
| el | Elevation (rad) |
| tt | Turntable angle (rad) |
| qECIToBody | Quaternion from ECI to Body |
| mBaseToBody | Transformation matrix from Camera base to body |
| ml_matrix eci_to_ned | ( | const ml_matrix & | r, |
| int | opt, | ||
| double | f | ||
| ) |
Computes the transformation matrix or quaternion from a eciframe to the North East Down (NED) frame.
Computes the transformation matrix or quaternion from a eciframe to the North East Down (NED) frame.
Reference: Stevens, B.L., Lewis, F.L. , Aircraft Control and Simulation, John Wiley & Sons, 1992, p. 36.
| r | ECI position vector (km) |
| opt | 0 output quaternion 1 output matrix (rad) |
| f | Flattening factor |
References mat_to_q().
Referenced by gps_eci_state_from_data().
| ml_matrix u_to_az_el | ( | const ml_matrix & | u | ) |
Computes the azimuth and elevation of a unit vector.
Computes the azimuth and elevation of a unit vector.
| u | Unit vector |
Referenced by u_eci_to_az_el_body().
| ml_matrix u_to_x_z | ( | const ml_matrix & | u | ) |
Computes the x and z rotations to align z with a unit vector.
Compute azimuth and elevation from a unit vector.
| u | Unit vector |
| ml_matrix az_el_to_u | ( | double | az, |
| double | el | ||
| ) |
Computes u from azimuth and elevation of a unit vector.
Computes u from azimuth and elevation of a unit vector.
| az | Azimuth |
| el | Elevation |
| ml_matrix az_el_to_u | ( | const ml_matrix & | az, |
| const ml_matrix & | el | ||
| ) |
Compute a unit vector from azimuth and elevation.
Compute a unit vector from azimuth and elevation.
| az | is the azimuth (angle about +z from +x) |
| el | is the elevation (angle about +y from +x) |
| ml_matrix q_from_dq | ( | const ml_matrix & | q, |
| const ml_matrix & | dX | ||
| ) |
Computes q as the product of q and a delta quaternion.
Computes q as the product of q and a delta quaternion.
| q | Quaternion |
| dX | Delta quaternion |
References dq_from_dX().
| ml_matrix dq_from_dX | ( | const ml_matrix & | dX | ) |
Delta quaternion from a 3 vector.
Delta quaternion from a 3 vector.
| dX | Delta quaternion |
Referenced by q_from_dq().
| ml_matrix r_lvlh_to_eci | ( | const ml_matrix & | r_eci, |
| const ml_matrix & | v_eci, | ||
| const ml_matrix & | r | ||
| ) |
LVLH position to ECI.
LVLH position to ECI.
| r_eci | Position vector of reference center in the ECI frame |
| v_eci | Velocity vector of reference center in the ECI frame |
| r | Position vector in lvlh frame |
References q_eci_to_lvlh().
| ml_matrix v_lvlh_to_eci | ( | const ml_matrix & | r_eci, |
| const ml_matrix & | v_eci, | ||
| const ml_matrix & | v | ||
| ) |
ECI position to LVLH.
ECI position to LVLH.
| r_eci | Position vector of reference center in the ECI frame |
| v_eci | Velocity vector of reference center in the ECI frame |
| v | Position vector in lvlh frame |
References q_eci_to_lvlh().
| ml_matrix r_eci_to_lvlh | ( | const ml_matrix & | r_eci, |
| const ml_matrix & | v_eci, | ||
| const ml_matrix & | r | ||
| ) |
LVLH position to ECI.
LVLH position to ECI.
| r_eci | Position vector of reference center in the ECI frame |
| v_eci | Velocity vector of reference center in the ECI frame |
| r | Position vector in eci frame |
References q_eci_to_lvlh().
| ml_matrix v_eci_to_lvlh | ( | const ml_matrix & | r_eci, |
| const ml_matrix & | v_eci, | ||
| const ml_matrix & | v | ||
| ) |
ECI position to LVLH.
ECI position to LVLH.
| r_eci | Position vector of reference center in the ECI frame |
| v_eci | Velocity vector of reference center in the ECI frame |
| v | Position vector in eci frame |
References q_eci_to_lvlh().
| ml_matrix x_lvlh_to_eci | ( | const ml_matrix & | r_eci, |
| const ml_matrix & | v_eci, | ||
| const ml_matrix & | x | ||
| ) |
LVLH state to ECI.
LVLH state to ECI.
| r_eci | Position vector of reference center in the ECI frame |
| v_eci | Velocity vector of reference center in the ECI frame |
| x | [r;v] in lvlh frame |
References q_eci_to_lvlh().
| ml_matrix x_eci_to_lvlh | ( | const ml_matrix & | r_eci, |
| const ml_matrix & | v_eci, | ||
| const ml_matrix & | x | ||
| ) |
ECI state to LVLH.
ECI state to LVLH.
| r_eci | Position vector of reference center in the ECI frame |
| v_eci | Velocity vector of reference center in the ECI frame |
| x | [r;v] in eci frame |
References q_eci_to_lvlh().
| ml_matrix x_lvlh_to_eci | ( | const ml_matrix & | x_eci, |
| const ml_matrix & | x | ||
| ) |
ECI state to LVLH.
ECI state to LVLH.
| x_eci | Velocity vector of reference center in the ECI frame |
| x | [r;v] in lvlh frame |
References q_eci_to_lvlh().
| ml_matrix x_eci_to_lvlh | ( | const ml_matrix & | x_eci, |
| const ml_matrix & | x | ||
| ) |
ECI state to LVLH.
ECI state to LVLH.
| x_eci | State vector of reference center in the ECI frame [r;v] |
| x | [r;v] in eci frame |
References q_eci_to_lvlh().
| ml_matrix LLAToECEF | ( | const ml_matrix & | lla, |
| double | rP | ||
| ) |
Compute ECEF position from latitude, longitude, altitude.
Compute ECEF position from latitude, longitude, altitude.
Assumes a spherical planet. Can handle an array of positions.
| lla | (3xn) Latitude [rad], longitude [rad], altitude [km] |
| rP | Radius of planet (for Earth: 6378.14) [km] |
| ml_matrix small_angles_to_q | ( | const ml_matrix & | angle | ) |
Convert small angles to a quaternion.
| angle | Angle vector |
| ml_matrix spice_to_3_by_3 | ( | const ml_matrix & | m, |
| int | k | ||
| ) |
Convert SPICE rotation matrix to 3x3.
Convert SPICE rotation matrix to 3x3.
| m | SPICE 9-by-1 rotation matrix (column major) |
| k | Column |
| double esd_to_azim | ( | const ml_matrix & | u | ) |
Convert an East-South-Down vector to azimuth from North.
| u | Unit vector in ESD frame |
References PI.
Referenced by beam_contour::rotateAxis().
| double esd_to_elev | ( | const ml_matrix & | u | ) |
Convert an East-South-Down vector to elevation from nadir.
| u | Unit vector in ESD frame |
Referenced by beam_contour::rotateAxis().
| ml_matrix azim_elev_to_esd | ( | const double & | azim, |
| const double & | elev | ||
| ) |
Convert azimuth / elevation angles to an East-South-Down unit vector.
| azim | Azimuth angle from North vector (rad) |
| elev | Elevation angle from nadir vector (rad) |
| ml_matrix ecef_to_esd | ( | const ml_matrix & | rEF | ) |
Compute rotation matrix from Earth-fixed frame to East-South-Down frame at given Earth-fixed position.
Compute rotation matrix from Earth-fixed frame to East-South-Down frame at given Earth-fixed position.
| rEF | Earth-fixed position |
| ml_matrix u_eci_to_az_el_body | ( | const ml_matrix & | u_eci, |
| const ml_matrix & | q_eci_to_body, | ||
| const ml_matrix & | q_body_to_base | ||
| ) |
Find az and el from an ECI vector.
| u_eci | Vector in eci |
| q_eci_to_body | Quaternion from ecu to body frame |
| q_body_to_sensor | Quaternion from body to sensor frame |
References u_to_az_el().
| sun_vector_out sun_vector_pointing | ( | const ml_matrix & | u_eci, |
| const ml_matrix & | u_sun_eci | ||
| ) |
Rotation angles to point a solar wing at the sun.
Rotation angles to point a solar wing at the sun.
| u_eci | x-axis vector in |
| u_sun_eci | Sun vector in eci |
References sun_vector_out_s::angle_solar_wing, mat_to_q(), sun_vector_out_s::q_eci_to_body, and u_to_q().
| ml_matrix target_from_r_v_d | ( | const ml_matrix & | r, |
| double | r_p, | ||
| const ml_matrix & | v, | ||
| double | d | ||
| ) |
Landing target.
Landing target.
| r | Position vector of spacecraft |
| r_p | Planet radius |
| v | Velocity vector |
| d | Downrange distance |
References au_to_q().