Transformations
Helper functions for ROS messaging
Classes:
BBox (left, bottom, right, top) | Create new instance of BBox(left, bottom, right, top) |
---|
Functions:
add_transform_stamped (transform1, transform2) | |
---|---|
affine_to_proj (M) | Returns a PROJ string describing a CRS that is defined by converting the image pixel coordinates (x, y) to WGS 84 coordinates (lon, lat) using the provided affine transformation. |
angle_off_nadir (quaternion) | Angle off nadir in radians |
as_np_quaternion (q) | Converts ROS geometric_msg.msg.Quaternion to (x, y, z, w) format numpy array quaternion |
as_ros_quaternion (q) | Converts (x, y, z, w) format numpy array quaternion to ROS geometric_msg.msg.Quaternion |
bounding_box_to_bbox (msg) | Converts geographic_msgs.msg.BoundingBox to BBox |
create_identity_pose_stamped (x, y, z) | |
create_pose_msg (stamp, frame_id, r, t) | |
create_transform_msg (stamp, parent_frame, ...) | |
ecef_to_wgs84 (x, y, z) | Convert ECEF (Earth-Centered, Earth-Fixed) coordinates to WGS 84 geodetic coordinates. |
enu_to_ecef_matrix (lon, lat) | Generate the rotation matrix for converting ENU coordinates at a given longitude (lon) and latitude (lat) to ECEF coordinates. |
extract_roll (q) | Calculate the roll angle from a quaternion |
extract_yaw (q) | Calculate the yaw angle from a quaternion in the ENU frame. |
get_transform (node, target_frame, ...) | |
lookup_transform (buffer, target_frame, ...) | Returns transform from source to target frame, or None if not available |
matrices_to_homogenous (r, t) | 3D pose in homogenous form for convenience |
pose_to_transform (pose_stamped_msg, ...) | |
poses_to_twist (pose2, pose1) | pose2 is newer pose with covariances, pose1 is older pose (identity pose in VO) |
proj_to_affine (proj_str) | Returns the affine transformation matrix M that corresponds to the provided PROJ string. |
transform_to_pose (transform_stamped_msg) | |
usec_from_header (header) | Returns timestamp in microseconds from std_msgs.msg.Header stamp |
wgs84_to_ecef (lon, lat, alt) | Convert WGS 84 geodetic coordinates to ECEF (Earth-Centered, Earth-Fixed) coordinates. |
class gisnav._transformations.BBox(left, bottom, right, top)
Bases: tuple
Create new instance of BBox(left, bottom, right, top)
Attributes:
bottom | Alias for field number 1 |
---|---|
left | Alias for field number 0 |
right | Alias for field number 2 |
top | Alias for field number 3 |
bottom
Alias for field number 1
left
Alias for field number 0
right
Alias for field number 2
top
Alias for field number 3
gisnav._transformations.add_transform_stamped(transform1: TransformStamped | PoseStamped, transform2: TransformStamped)
gisnav._transformations.affine_to_proj(M: ndarray)
Returns a PROJ string describing a CRS that is defined by converting the image pixel coordinates (x, y) to WGS 84 coordinates (lon, lat) using the provided affine transformation.
- Returns: PROJ string representing the affine transformation
gisnav._transformations.angle_off_nadir(quaternion)
Angle off nadir in radians
gisnav._transformations.as_np_quaternion(q: Quaternion)
Converts ROS geometric_msg.msg.Quaternion
to (x, y, z, w) format numpy array quaternion
- Parameters:q – ROS quaternion message
- Returns: NumPy array quaternion in (x, y, z, w) format
gisnav._transformations.as_ros_quaternion(q: ndarray)
Converts (x, y, z, w) format numpy array quaternion to ROS geometric_msg.msg.Quaternion
- Parameters:q – NumPy array quaternion of shape in (x, y, z, w) format
- Returns: ROS quaternion message
gisnav._transformations.bounding_box_to_bbox(msg: BoundingBox)
Converts geographic_msgs.msg.BoundingBox
to BBox
gisnav._transformations.create_identity_pose_stamped(x, y, z)
gisnav._transformations.create_pose_msg(stamp: Time, frame_id: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'], r: ndarray, t: ndarray)
gisnav._transformations.create_transform_msg(stamp, parent_frame: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'], child_frame: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'], q: tuple, translation_vector: ndarray)
gisnav._transformations.ecef_to_wgs84(x: float, y: float, z: float)
Convert ECEF (Earth-Centered, Earth-Fixed) coordinates to WGS 84 geodetic coordinates.
- Parameters:
- x – ECEF x-coordinate in meters.
- y – ECEF y-coordinate in meters.
- z – ECEF z-coordinate in meters.
- Returns: A tuple (lon, lat, alt) representing longitude, latitude, and altitude in the WGS84 coordinate system.
Uses the Proj4 library to transform from Cartesian coordinates (x, y, z) in the ECEF system (earth
frame in REP 105) to geographic (latitude, longitude, altitude) coordinates.
gisnav._transformations.enu_to_ecef_matrix(lon: float, lat: float)
Generate the rotation matrix for converting ENU coordinates at a given longitude (lon) and latitude (lat) to ECEF coordinates.
- Parameters:
- lon – Longitude in decimal degrees.
- lat – Latitude in decimal degrees.
- Returns: Rotation matrix (3x3) for the transformation.
gisnav._transformations.extract_roll(q: Quaternion)
Calculate the roll angle from a quaternion
- Parameters:q – A quaternion represented as a Quaternion object in (x, y, z, w) format
- Returns: The roll angle in degrees
gisnav._transformations.extract_yaw(q: Quaternion)
Calculate the yaw angle from a quaternion in the ENU frame.
Returns yaw with origin centered at North (i.e. applies a 90 degree adjustment).
- Parameters:q – A list containing the quaternion [qx, qy, qz, qw].
- Returns: The yaw angle in degrees.
gisnav._transformations.get_transform(node: Node, target_frame: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'], source_frame: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'], stamp: Time)
gisnav._transformations.lookup_transform(buffer: Buffer, target_frame: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'], source_frame: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'], time_duration: Tuple[Time, Duration] | None = None, logger=None)
Returns transform from source to target frame, or None if not available
gisnav._transformations.matrices_to_homogenous(r, t)
3D pose in homogenous form for convenience
gisnav._transformations.pose_to_transform(pose_stamped_msg: PoseStamped | PoseWithCovarianceStamped, child_frame_id: Literal['base_link', 'camera', 'camera_optical', 'base_link_stabilized', 'camera_frd', 'map', 'odom', 'earth', 'gisnav_map', 'gisnav_odom', 'gisnav_camera_link_optical', 'gisnav_base_link', 'query_image'])
gisnav._transformations.poses_to_twist(pose2: PoseWithCovarianceStamped, pose1: PoseStamped)
pose2 is newer pose with covariances, pose1 is older pose (identity pose in VO)
gisnav._transformations.proj_to_affine(proj_str: str)
Returns the affine transformation matrix M that corresponds to the provided PROJ string. The PROJ string should be in the format used by the affine_to_proj function.
- Parameters:proj_str – PROJ string representing an affine transformation
- Returns: 3x3 affine transformation matrix M
gisnav._transformations.transform_to_pose(transform_stamped_msg: TransformStamped)
gisnav._transformations.usec_from_header(header: Header)
Returns timestamp in microseconds from std_msgs.msg.Header
stamp
gisnav._transformations.wgs84_to_ecef(lon: float, lat: float, alt: float)
Convert WGS 84 geodetic coordinates to ECEF (Earth-Centered, Earth-Fixed) coordinates.
- Parameters:
- lon – Longitude in decimal degrees.
- lat – Latitude in decimal degrees.
- alt – Altitude above the WGS84 ellipsoid in meters.
- Returns: A tuple (x, y, z) representing ECEF coordinates in meters.
Uses the Proj4 library to transform from geographic (latitude, longitude, altitude) coordinates to Cartesian coordinates (x, y, z) in the ECEF system (earth
frame in REP 105).
GISNav v0.68.1-2-gf2c72641