Skip to content

Commit 5187402

Browse files
authored
Merge pull request #120 from hmakelin/enable-vo
Enable visual odometry
2 parents 24546b8 + fc0fc44 commit 5187402

File tree

7 files changed

+184
-25
lines changed

7 files changed

+184
-25
lines changed

docker/px4/6011_typhoon_h480

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,8 @@ param set-default EKF2_REQ_VDRIFT 1.5 # max value
1616
param set-default EKF2_REQ_SACC 5.0 # max value
1717
param set-default EKF2_HEAD_NOISE 1.0 # max value
1818
param set-default SENS_GPS_MASK 7
19-
param set-default EKF2_GPS_CTRL 8 # lon/lat, alt, 3D vel, heading
20-
param set-default EKF2_GPS_CHECK 0
19+
param set-default EKF2_GPS_CTRL 15 # max: lon/lat, alt, 3D vel, heading
20+
#param set-default EKF2_GPS_CHECK 0
2121

2222
# Secondary GPS (GISNav) at GPS 2 serial port via NMEA
2323
# https://docs.px4.io/v1.14/en/hardware/serial_port_mapping.html#default-px4board

gisnav/gisnav/_transformations.py

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
PoseWithCovarianceStamped,
1515
Quaternion,
1616
TransformStamped,
17+
TwistWithCovarianceStamped,
1718
)
1819
from pyproj import Proj, transform
1920
from rclpy.node import Node
@@ -411,3 +412,80 @@ def enu_to_ecef_matrix(lon: float, lat: float) -> np.ndarray:
411412
]
412413
)
413414
return R
415+
416+
417+
def poses_to_twist(
418+
pose2: PoseWithCovarianceStamped, pose1: PoseStamped
419+
) -> TwistWithCovarianceStamped:
420+
"""pose2 is newer pose with covariances, pose1 is older pose (identity pose in
421+
VO)
422+
"""
423+
# Time step between poses
424+
t2, t1 = usec_from_header(pose2.header), usec_from_header(pose1.header)
425+
426+
time_step = (t2 - t1) / 1e6 # seconds
427+
428+
# Calculate linear velocities
429+
dx = pose2.pose.pose.position.x - pose1.pose.position.x
430+
dy = pose2.pose.pose.position.y - pose1.pose.position.y
431+
dz = pose2.pose.pose.position.z - pose1.pose.position.z
432+
433+
# Calculate angular velocities using quaternion differences
434+
q1 = [
435+
pose1.pose.orientation.x,
436+
pose1.pose.orientation.y,
437+
pose1.pose.orientation.z,
438+
pose1.pose.orientation.w,
439+
]
440+
q2 = [
441+
pose2.pose.pose.orientation.x,
442+
pose2.pose.pose.orientation.y,
443+
pose2.pose.pose.orientation.z,
444+
pose2.pose.pose.orientation.w,
445+
]
446+
447+
q_diff = tf_transformations.quaternion_multiply(
448+
q2, tf_transformations.quaternion_inverse(q1)
449+
)
450+
451+
# Converting quaternion to rotation vector (axis-angle)
452+
angle = 2 * np.arccos(q_diff[3]) # Compute the rotation angle
453+
axis = q_diff[:3] / np.sin(angle / 2) # Normalize the axis
454+
rotation_vector = angle * axis # Multiply angle by the normalized axis
455+
456+
ang_vel = rotation_vector / time_step
457+
458+
# Create TwistStamped message
459+
twist = TwistWithCovarianceStamped()
460+
twist.header.stamp = pose2.header.stamp
461+
twist.header.frame_id = pose2.header.frame_id
462+
twist.twist.twist.linear.x = dx / time_step
463+
twist.twist.twist.linear.y = dy / time_step
464+
twist.twist.twist.linear.z = dz / time_step
465+
twist.twist.twist.angular.x = ang_vel[0]
466+
twist.twist.twist.angular.y = ang_vel[1]
467+
twist.twist.twist.angular.z = ang_vel[2]
468+
469+
twist.twist.covariance = pose2.pose.covariance # todo: could make these smaller?
470+
471+
return twist
472+
473+
474+
def create_identity_pose_stamped(x, y, z):
475+
pose_stamped = PoseStamped()
476+
477+
pose_stamped.header.stamp = rclpy.time.Time().to_msg()
478+
pose_stamped.header.frame_id = "camera_optical"
479+
480+
# Set the position coordinates
481+
pose_stamped.pose.position.x = x
482+
pose_stamped.pose.position.y = y
483+
pose_stamped.pose.position.z = z
484+
485+
# Set the orientation to identity (no rotation)
486+
pose_stamped.pose.orientation.x = 0.0
487+
pose_stamped.pose.orientation.y = 0.0
488+
pose_stamped.pose.orientation.z = 0.0
489+
pose_stamped.pose.orientation.w = 1.0
490+
491+
return pose_stamped

gisnav/gisnav/constants.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,9 +64,9 @@
6464
:attr:`.StereoNode.pose`.
6565
6666
"""
67-
ROS_TOPIC_RELATIVE_QUERY_POSE: Final = "~/vo/pose"
67+
ROS_TOPIC_RELATIVE_QUERY_TWIST: Final = "~/vo/twist"
6868
"""Relative :term:`topic` into which :class:`.StereoNode` publishes
69-
:attr:`.StereoNode.camera_optical_pose_in_query_frame`.
69+
:attr:`.StereoNode.camera_optical_twist_in_query_frame`.
7070
"""
7171

7272
MAVROS_TOPIC_TIME_REFERENCE: Final = "/mavros/time_reference"

gisnav/gisnav/core/pose_node.py

Lines changed: 91 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
The pose is estimated by finding matching keypoints between the query and
99
reference images and then solving the resulting :term:`PnP` problem.
1010
"""
11-
from typing import Optional, Tuple, Union, cast
11+
from typing import Final, Optional, Tuple, Union, cast
1212

1313
import cv2
1414
import numpy as np
@@ -18,11 +18,16 @@
1818
import torch
1919
from builtin_interfaces.msg import Time
2020
from cv_bridge import CvBridge
21-
from geometry_msgs.msg import PoseWithCovariance, PoseWithCovarianceStamped
21+
from geometry_msgs.msg import (
22+
PoseWithCovariance,
23+
PoseWithCovarianceStamped,
24+
TwistWithCovarianceStamped,
25+
)
2226
from kornia.feature import DISK, LightGlueMatcher, laf_from_center_scale_ori
2327
from rclpy.node import Node
2428
from rclpy.qos import QoSPresetProfiles
2529
from robot_localization.srv import SetPose
30+
from scipy.interpolate import interp1d
2631
from sensor_msgs.msg import CameraInfo, Image, TimeReference
2732

2833
from gisnav_msgs.msg import ( # type: ignore[attr-defined]
@@ -38,7 +43,7 @@
3843
ROS_TOPIC_CAMERA_INFO,
3944
ROS_TOPIC_RELATIVE_POSE,
4045
ROS_TOPIC_RELATIVE_POSE_IMAGE,
41-
ROS_TOPIC_RELATIVE_QUERY_POSE,
46+
ROS_TOPIC_RELATIVE_QUERY_TWIST,
4247
ROS_TOPIC_RELATIVE_TWIST_IMAGE,
4348
STEREO_NODE_NAME,
4449
FrameID,
@@ -74,6 +79,39 @@ class PoseNode(Node):
7479
MIN_MATCHES = 30
7580
"""Minimum number of keypoint matches before attempting pose estimation"""
7681

82+
class ScalingBuffer:
83+
"""Maintains timestamped query frame to world frame scaling in a sliding windown
84+
buffer so that shallow matching (VO) pose can be scaled to meters using
85+
scaling information obtained from deep matching
86+
"""
87+
88+
_WINDOW_LENGTH: Final = 100
89+
90+
def __init__(self):
91+
self._scaling_arr: np.ndarray = np.ndarray([])
92+
self._timestamp_arr: np.ndarray = np.ndarray([])
93+
94+
def append(self, timestamp_usec: int, scaling: float) -> None:
95+
self._scaling_arr = np.append(self._scaling_arr, scaling)
96+
self._timestamp_arr = np.append(self._timestamp_arr, timestamp_usec)
97+
98+
if self._scaling_arr.size > self._WINDOW_LENGTH:
99+
self._scaling_arr[-self._WINDOW_LENGTH :]
100+
if self._timestamp_arr.size > self._WINDOW_LENGTH:
101+
self._timestamp_arr[-self._WINDOW_LENGTH :]
102+
103+
def interpolate(self, timestamp_usec: int) -> Optional[float]:
104+
if self._scaling_arr.size < 2:
105+
return None
106+
107+
interp_function = interp1d(
108+
self._timestamp_arr,
109+
self._scaling_arr,
110+
kind="linear",
111+
fill_value="extrapolate",
112+
)
113+
return interp_function(timestamp_usec)
114+
77115
def __init__(self, *args, **kwargs):
78116
"""Class initializer
79117
@@ -114,7 +152,7 @@ def __init__(self, *args, **kwargs):
114152
# initialize publishers (for launch tests)
115153
self.pose
116154
# TODO method does not support none input
117-
self.camera_optical_pose_in_query_frame(None)
155+
self.camera_optical_twist_in_camera_optical_frame(None)
118156

119157
self._tf_buffer = tf2_ros.Buffer()
120158
self._tf_listener = tf2_ros.TransformListener(self._tf_buffer, self)
@@ -127,6 +165,8 @@ def __init__(self, *args, **kwargs):
127165
self._set_pose_request = SetPose.Request()
128166
self._pose_sent = False
129167

168+
self._scaling_buffer = self.ScalingBuffer()
169+
130170
def _set_initial_pose(self, pose):
131171
if not self._pose_sent:
132172
self._set_pose_request.pose = pose
@@ -160,7 +200,7 @@ def _pose_image_cb(self, msg: Image) -> None:
160200

161201
def _twist_image_cb(self, msg: Image) -> None:
162202
"""Callback for :attr:`.twist_image` message"""
163-
self.camera_optical_pose_in_query_frame(self.twist_image)
203+
self.camera_optical_twist_in_camera_optical_frame(self.twist_image)
164204

165205
@property
166206
@ROS.publish(
@@ -202,6 +242,7 @@ def _get_pose(
202242
r, t = pose
203243

204244
r_inv = r.T
245+
205246
camera_optical_position_in_world = -r_inv @ t
206247

207248
tf_.visualize_camera_position(
@@ -212,15 +253,38 @@ def _get_pose(
212253
f"{'shallow' if shallow_inference else 'deep'} inference",
213254
)
214255

256+
if isinstance(msg, MonocularStereoImage):
257+
scaling = self._scaling_buffer.interpolate(
258+
tf_.usec_from_header(msg.query.header)
259+
)
260+
if scaling is not None:
261+
camera_optical_position_in_world = (
262+
camera_optical_position_in_world * scaling
263+
)
264+
else:
265+
self.get_logger().debug(
266+
"No scaling availble for VO - will not return VO pose"
267+
)
268+
return None
269+
215270
pose = tf_.create_pose_msg(
216271
msg.query.header.stamp,
217-
cast(FrameID, "earth"),
272+
cast(FrameID, "earth")
273+
if isinstance(msg, OrthoStereoImage)
274+
else cast(FrameID, "camera_optical"),
218275
r_inv,
219276
camera_optical_position_in_world,
220277
)
221278

222279
if isinstance(msg, OrthoStereoImage):
223280
affine = tf_.proj_to_affine(msg.crs.data)
281+
282+
# use z scaling value
283+
usec = tf_.usec_from_header(msg.query.header)
284+
scaling = np.abs(affine[2, 2])
285+
if usec is not None and scaling is not None:
286+
self._scaling_buffer.append(usec, scaling)
287+
224288
t_wgs84 = affine @ np.append(camera_optical_position_in_world, 1)
225289
x, y, z = tf_.wgs84_to_ecef(*t_wgs84.tolist())
226290
pose.pose.position.x = x
@@ -254,16 +318,33 @@ def _get_pose(
254318
return pose_with_covariance
255319

256320
@ROS.publish(
257-
ROS_TOPIC_RELATIVE_QUERY_POSE,
321+
ROS_TOPIC_RELATIVE_QUERY_TWIST,
258322
QoSPresetProfiles.SENSOR_DATA.value,
259323
)
260324
# @ROS.transform("camera_optical") # TODO: enable after scaling to meters
261325
@narrow_types
262-
def camera_optical_pose_in_query_frame(
326+
def camera_optical_twist_in_camera_optical_frame(
263327
self, msg: MonocularStereoImage
264-
) -> Optional[PoseWithCovarianceStamped]:
328+
) -> Optional[TwistWithCovarianceStamped]:
265329
"""Camera pose in visual odometry world frame (i.e. previous query frame)"""
266-
return self._get_pose(msg)
330+
scaling = self._scaling_buffer.interpolate(
331+
tf_.usec_from_header(msg.query.header)
332+
)
333+
if scaling is None:
334+
return None
335+
336+
x, y, z = (
337+
scaling * 320.0,
338+
scaling * 180.0,
339+
scaling * -205.0,
340+
) # todo do not hard code
341+
previous_pose = tf_.create_identity_pose_stamped(x, y, z)
342+
previous_pose.header = msg.reference.header
343+
current_pose = self._get_pose(msg)
344+
if current_pose is not None:
345+
return tf_.poses_to_twist(current_pose, previous_pose)
346+
else:
347+
return None
267348

268349
@property
269350
# @ROS.max_delay_ms(DELAY_DEFAULT_MS)

gisnav/gisnav/core/stereo_node.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ def __init__(self, *args, **kwargs) -> None:
7171
# setup publisher to pass launch test without image callback being
7272
# triggered
7373
self.pose_image
74-
# self.twist_image # todo re-enable once scaling is solved
74+
self.twist_image
7575

7676
# Initialize the transform broadcaster and listener
7777
self._tf_buffer = tf2_ros.Buffer()
@@ -99,8 +99,7 @@ def _image_cb(self, msg: Image) -> None:
9999
"""Callback for :attr:`.image` message"""
100100
self.pose_image # publish rotated and cropped orthoimage stack
101101

102-
# TODO: re-enable once proper scaling is implemented for VO
103-
# self.twist_image # publish two subsequent images for VO
102+
self.twist_image # publish two subsequent images for VO
104103

105104
# TODO this is brittle - nothing is enforcing that this is assigned after
106105
# publishing stereo_image

gisnav/launch/params/ekf_node.yaml

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -29,12 +29,13 @@ robot_localization:
2929
# Fuse absolute pose estimated from map rasters
3030
pose0: "/gisnav/pose_node/pose"
3131
pose0_config: [true, true, true, # Position XYZ
32-
true, true, true, # Orientation (roll, pitch, yaw)
32+
false, false, false, #true, true, true, # Orientation (roll, pitch, yaw)
3333
false, false, false, # Velocity XYZ
3434
false, false, false, # Angular rates XYZ
3535
false, false, false] # Accelerations XYZ
3636

3737
# Fuse smooth relative pose estimated via VO differentially as velocity
38+
# - better than a lagging velocity from pose0
3839
#pose1: "/gisnav/pose_node/vo/pose"
3940
#pose1_differential: true
4041
#pose1_config: [true, true, true, # Position XYZ
@@ -43,13 +44,12 @@ robot_localization:
4344
# false, false, false, # Angular rates XYZ
4445
# false, false, false] # Accelerations XYZ
4546

46-
#pose1: "/gisnav/pose_node/vo/pose"
47-
#pose1_differential: true
48-
#pose1_config: [false, false, false, # Position XYZ
49-
# false, false, false, # Orientation (roll, pitch, yaw)
50-
# true, true, true, # Velocity XYZ
51-
# true, true, true, # Angular rates XYZ
52-
# false, false, false] # Accelerations XYZ
47+
twist1: "/gisnav/pose_node/vo/twist"
48+
twist1_config: [false, false, false, # Position XYZ
49+
false, false, false, # Orientation (roll, pitch, yaw)
50+
true, true, true, # Velocity XYZ
51+
true, true, true, # Angular rates XYZ
52+
false, false, false] # Accelerations XYZ
5353

5454
#debug: true
5555
#debug_out_file: "/home/hmakelin/robot_localization_debug.txt"

gisnav/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
<depend>python3-setuptools</depend> <!-- setuptools is build dependency only? -->
4747
<depend>python3-shapely</depend>
4848
<depend>python3-serial</depend>
49+
<depend>python3-scipy</depend>
4950
<!-- <depend>python3-owslib</depend> not found by rosdep, in setup.py instead -->
5051

5152
<!-- need these to install things from setup.py -->

0 commit comments

Comments
 (0)