• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

lunarlab-gatech / robotdataprocess / 20820881882

08 Jan 2026 02:50PM UTC coverage: 62.482% (-12.2%) from 74.672%
20820881882

Pull #10

github

DanielChaseButterfield
Add publish script for OpenVINS
Pull Request #10: (v0.2) Prototype code for ROS2 Publishing, and new ImageDataOnDisk class

181 of 277 branches covered (65.34%)

Branch coverage included in aggregate %.

212 of 546 new or added lines in 11 files covered. (38.83%)

3 existing lines in 2 files now uncovered.

1118 of 1802 relevant lines covered (62.04%)

1.24 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

76.35
/src/robotdataprocess/data_types/OdometryData.py
1
from __future__ import annotations
2✔
2

3
from ..conversion_utils import col_to_dec_arr
2✔
4
import csv
2✔
5
from .Data import CoordinateFrame, Data, ROSMsgLibType
2✔
6
import decimal
2✔
7
from decimal import Decimal
2✔
8
from evo.core import geometry
2✔
9
import matplotlib.pyplot as plt
2✔
10
import numpy as np
2✔
11
from numpy.typing import NDArray
2✔
12
import os
2✔
13
import pandas as pd
2✔
14
from .PathData import PathData
2✔
15
from pathlib import Path
2✔
16
from ..ros.Ros2BagWrapper import Ros2BagWrapper
2✔
17
from rosbags.rosbag2 import Reader as Reader2
2✔
18
from rosbags.typesys import Stores, get_typestore
2✔
19
from rosbags.typesys.store import Typestore
2✔
20
from scipy.spatial.transform import Rotation as R
2✔
21
from typeguard import typechecked
2✔
22
from typing import Union, List, Tuple
2✔
23
import tqdm
2✔
24

25
@typechecked
2✔
26
class OdometryData(PathData):
2✔
27

28
    # Define odometry-specific data attributes
29
    child_frame_id: str
2✔
30
    poses: list # Saved nav_msgs/msg/Pose
2✔
31

32
    @typechecked
2✔
33
    def __init__(self, frame_id: str, child_frame_id: str, timestamps: Union[np.ndarray, list], 
2✔
34
                 positions: Union[np.ndarray, list], orientations: Union[np.ndarray, list], frame: CoordinateFrame):
35
        
36
        # Copy initial values into attributes
37
        super().__init__(frame_id, timestamps, positions, orientations, frame)
2✔
38
        self.child_frame_id: str = child_frame_id
2✔
39
        self.poses: list = []
2✔
40

41
        # Check to ensure that all arrays have same length
42
        if len(self.timestamps) != len(self.positions) or len(self.positions) != len(self.orientations):
2✔
43
            raise ValueError("Lengths of timestamp, position, and orientation arrays are not equal!")
×
44

45
    # =========================================================================
46
    # ============================ Class Methods ============================== 
47
    # =========================================================================  
48

49
    @classmethod
2✔
50
    @typechecked
2✔
51
    def from_ros2_bag(cls, bag_path: Union[Path, str], odom_topic: str, frame: CoordinateFrame):
2✔
52
        """
53
        Creates a class structure from a ROS2 bag file with an Odometry topic.
54

55
        Args:
56
            bag_path (Path | str): Path to the ROS2 bag file.
57
            odom_topic (str): Topic of the Odometry messages.
58
        Returns:
59
            OdometryData: Instance of this class.
60
        """
61

62
        # Get topic message count and typestore
63
        bag_wrapper = Ros2BagWrapper(bag_path, None)
2✔
64
        typestore: Typestore = bag_wrapper.get_typestore()
2✔
65
        num_msgs: int = bag_wrapper.get_topic_count(odom_topic)
2✔
66
        
67
        # Pre-allocate arrays (memory-mapped or otherwise)
68
        timestamps_np = np.zeros(num_msgs, dtype=Decimal)
2✔
69
        positions_np = np.zeros((num_msgs, 3), dtype=Decimal)
2✔
70
        orientations_np = np.zeros((num_msgs, 4), dtype=Decimal)
2✔
71

72
        # Setup tqdm bar & counter
73
        pbar = tqdm.tqdm(total=num_msgs, desc="Extracting Odometry...", unit=" msgs")
2✔
74
        i = 0
2✔
75

76
        # Extract the odometry information
77
        frame_id, child_frame_id = None, None
2✔
78
        with Reader2(str(bag_path)) as reader:
2✔
79

80
            # Extract frames from first message
81
            connections = [x for x in reader.connections if x.topic == odom_topic]
2✔
82
            for conn, timestamp, rawdata in reader.messages(connections=connections):  
2✔
83
                msg = typestore.deserialize_cdr(rawdata, conn.msgtype)
2✔
84
                frame_id = msg.header.frame_id
2✔
85
                child_frame_id = msg.child_frame_id
2✔
86
                break
2✔
87

88
            # Extract individual message data
89
            connections = [x for x in reader.connections if x.topic == odom_topic]
2✔
90
            for conn, timestamp, rawdata in reader.messages(connections=connections):
2✔
91
                msg = typestore.deserialize_cdr(rawdata, conn.msgtype)
2✔
92
                
93
                timestamps_np[i] = bag_wrapper.extract_timestamp(msg)
2✔
94
                pos = msg.pose.pose.position
2✔
95
                positions_np[i] = np.array([Decimal(pos.x), Decimal(pos.y), Decimal(pos.z)])
2✔
96
                ori = msg.pose.pose.orientation
2✔
97
                orientations_np[i] = np.array([Decimal(ori.x), Decimal(ori.y), Decimal(ori.z), Decimal(ori.w)])
2✔
98

99
                # NOTE: Doesn't support Twist information currently
100

101
                # Increment the count
102
                i += 1
2✔
103
                pbar.update(1)
2✔
104

105
        # Create an OdometryData class
106
        return cls(frame_id, child_frame_id, timestamps_np, positions_np, orientations_np, frame)
2✔
107
    
108
    @classmethod
2✔
109
    @typechecked
2✔
110
    def from_csv(cls, csv_path: Union[Path, str], frame_id: str, child_frame_id: str, frame: CoordinateFrame,          
2✔
111
                 header_included: bool, column_to_data: Union[List[int], None] = None, 
112
                 separator: Union[str, None] = None, filter: Union[Tuple[str, str], None] = None,
113
                 ts_in_ns: bool = False, reorder_data: bool = False):
114
        """
115
        Creates a class structure from a csv file.
116

117
        Args:
118
            csv_path (Path | str): Path to the CSV file.
119
            frame_id (str): The frame that this odometry is relative to.
120
            child_frame_id (str): The frame whose pose is represented by this odometry.
121
            frame (CoordinateFrame): The coordinate system convention of this data.
122
            header_included (bool): If this csv file has a header, so we can remove it.
123
            column_to_data (list[int]): Tells the algorithms which columns in the csv contain which
124
                of the following data: ['timestamp', 'x', 'y', 'z', 'qw', 'qx', 'qy', 'qz']. Thus, 
125
                index 0 of column_to_data should be the column that timestamp data is found in the 
126
                csv file. Set to None to use [0,1,2,3,4,5,6,7].
127
            separator (str | None): The separator used in the csv file. If None, will use a comma by default.
128
            filter: A tuple of (column_name, value), where only rows with column_name == value will be kept. If
129
                csv file has no headers, then `column_name` should be the index of the column as a string.
130
            ts_in_ns (bool): If True, assumes timestamps are in nanoseconds and converts to seconds. Otherwise,
131
                assumes timestamps are already in seconds.
132
            reorder_data (bool): If True, reorders the data to be in order of timestamps. If False, 
133
                assumes data is already ordered by timestamp.
134

135
        Returns:
136
            OdometryData: Instance of this class.
137
        """
138

139
        # If column_to_data is None, assume default
140
        if column_to_data is None:
2✔
141
            column_to_data = [0,1,2,3,4,5,6,7]
2✔
142
        else:
143
            # Check column_to_data values are valid
144
            assert np.all(np.array(column_to_data) >= 0)
2✔
145
            assert len(column_to_data) == 8
2✔
146

147
        # Read the csv file
148
        header = 0 if header_included else None
2✔
149
        df1 = pd.read_csv(str(csv_path), header=header, index_col=False, sep=separator, engine='python')
2✔
150

151
        # Rename columns to standard names
152
        rename_dict = {}
2✔
153
        desired_data = ['timestamp', 'x', 'y', 'z', 'qw', 'qx', 'qy', 'qz']
2✔
154
        for j, ind in enumerate(column_to_data):
2✔
155
            rename_dict[df1.columns[ind]] = desired_data[j]
2✔
156
        df1 = df1.rename(columns=rename_dict)
2✔
157

158
        # Using the filter if provided, remove unwanted rows
159
        if filter is not None:
2✔
160
            df1 = df1[df1[filter[0]] == filter[1]]
2✔
161

162
        # Convert columns to NDArray[Decimal]
163
        timestamps_np = np.array([Decimal(str(ts)) for ts in df1['timestamp']], dtype=object)
2✔
164
        positions_np = np.array([[Decimal(str(x)), Decimal(str(y)), Decimal(str(z))] 
2✔
165
                                 for x, y, z in zip(df1['x'], df1['y'], df1['z'])], dtype=object)
166
        orientations_np = np.array([[Decimal(str(qx)), Decimal(str(qy)), Decimal(str(qz)), Decimal(str(qw))]
2✔
167
                                    for qx, qy, qz, qw in zip(df1['qx'], df1['qy'], df1['qz'], df1['qw'])], dtype=object)
168
        
169
        # If timestamps are in ns, convert to s
170
        if ts_in_ns:
2✔
171
            timestamps_np = timestamps_np / Decimal('1e9')
2✔
172

173
        # Reorder the data if needed
174
        if reorder_data:
2✔
NEW
175
            print("Warning: This code is not tested yet!")
×
NEW
176
            sort_indices = np.argsort(timestamps_np)
×
NEW
177
            timestamps_np = timestamps_np[sort_indices]
×
NEW
178
            positions_np = positions_np[sort_indices]
×
NEW
179
            orientations_np = orientations_np[sort_indices]
×
180

181
        # Create an OdometryData class
182
        return cls(frame_id, child_frame_id, timestamps_np, positions_np, orientations_np, frame)
2✔
183
    
184
    @classmethod
2✔
185
    @typechecked
2✔
186
    def from_txt_file(cls, file_path: Union[Path, str], frame_id: str, child_frame_id: str, frame: CoordinateFrame,
2✔
187
                      header_included: bool, column_to_data: Union[List[int], None] = None):
188
        """
189
        Creates a class structure from a text file, where the order of values
190
        in the files follows ['timestamp', 'x', 'y', 'z', 'qw', 'qx', 'qy', 'qz'].
191

192
        Args:
193
            file_path (Path | str): Path to the file containing the odometry data.
194
            frame_id (str): The frame where this odometry is relative to.
195
            child_frame_id (str): The frame whose pose is represented by this odometry.
196
            frame (CoordinateFrame): The coordinate system convention of this data.
197
            header_included (bool): If this text file has a header, so we can remove it.
198
            column_to_data (list[int]): Tells the algorithms which columns in the text file contain which
199
                of the following data: ['timestamp', 'x', 'y', 'z', 'qw', 'qx', 'qy', 'qz']. Thus, 
200
                index 0 of column_to_data should be the column that timestamp data is found in the 
201
                text file. Set to None to use [0,1,2,3,4,5,6,7].
202
        Returns:
203
            OdometryData: Instance of this class.
204
        """
205
        
206
        # If column_to_data is None, assume default
207
        if column_to_data is None:
2✔
208
            column_to_data = [0,1,2,3,4,5,6,7]
2✔
209
        else:
210
            # Check column_to_data values are valid
211
            assert np.all(np.array(column_to_data) >= 0)
2✔
212
            assert len(column_to_data) == 8
2✔
213

214
        # Count the number of lines in the file
215
        line_count = 0
2✔
216
        with open(str(file_path), 'r') as file:
2✔
217
            for _ in file: 
2✔
218
                line_count += 1
2✔
219

220
        # Setup arrays to hold data
221
        timestamps_np = np.zeros((line_count), dtype=object)
2✔
222
        positions_np = np.zeros((line_count, 3), dtype=object)
2✔
223
        orientations_np = np.zeros((line_count, 4), dtype=object)
2✔
224

225
        # Open the txt file and read in the data
226
        with open(str(file_path), 'r') as file:
2✔
227
            for i, line in enumerate(file):
2✔
228
                line_split = line.split(' ')
2✔
229
                timestamps_np[i] = line_split[column_to_data[0]]
2✔
230
                positions_np[i] = np.array([line_split[column_to_data[1]], line_split[column_to_data[2]], line_split[column_to_data[3]]])
2✔
231
                orientations_np[i] =  np.array([line_split[column_to_data[5]], line_split[column_to_data[6]], line_split[column_to_data[7]], line_split[column_to_data[4]]])
2✔
232

233
        # Remove the header
234
        if header_included:
2✔
235
            timestamps_np = timestamps_np[1:]
2✔
236
            positions_np = positions_np[1:]
2✔
237
            orientations_np = orientations_np[1:]
2✔
238
        
239
        # Create an OdometryData class
240
        return cls(frame_id, child_frame_id, timestamps_np, positions_np, orientations_np, frame)
2✔
241
    
242
    # =========================================================================
243
    # ========================= Manipulation Methods ========================== 
244
    # =========================================================================  
245
    
246
    def add_folded_guassian_noise_to_position(self, xy_noise_std_per_frame: float,
2✔
247
            z_noise_std_per_frame: float):
248
        """
249
        This method simulates odometry drift by adding folded gaussian noise
250
        to the odometry positions on a per frame basis. It also accumulates
251
        it over time. NOTE: It completely ignores the timestamps, and the "folded
252
        guassian noise" distribution stds might not align with the stds of the 
253
        guassian used internally, so this is not a robust function at all.
254

255
        Args:
256
            xy_noise_std_per_frame (float): Standard deviation of the gaussian 
257
                distribution for xy, whose output is then run through abs().
258
            z_noise_std_per_frame (float): Same as above, but for z.
259
        """
260

261
        # Track cumulative noise for each field
262
        cumulative_noise_pos = {'x': 0.0, 'y': 0.0, 'z': 0.0}
×
263

264
        # For each position
265
        for i in range(len(self.timestamps)):
×
266

267
            # Sample noise and accumulate
268
            noise_pos = {'x': np.random.normal(0, xy_noise_std_per_frame),
×
269
                        'y': np.random.normal(0, xy_noise_std_per_frame),
270
                        'z': np.random.normal(0, z_noise_std_per_frame)}
271
            for key in cumulative_noise_pos:
×
272
                cumulative_noise_pos[key] += abs(noise_pos[key])
×
273

274
            # Update positions
275
            self.positions[i][0] += Decimal(cumulative_noise_pos['x'])
×
276
            self.positions[i][1] += Decimal(cumulative_noise_pos['y'])
×
277
            self.positions[i][2] += Decimal(cumulative_noise_pos['z'])
×
278

279
    @typechecked
2✔
280
    def shift_position(self, x_shift: float, y_shift: float, z_shift: float):
2✔
281
        """
282
        Shifts the positions of the odometry.
283

284
        Args:
285
            x_shift (float): Shift in x-axis.
286
            y_shift (float): Shift in y_axis.
287
            z_shift (float): Shift in z_axis.
288
        """
289
        self.positions[:,0] += Decimal(x_shift)
×
290
        self.positions[:,1] += Decimal(y_shift)
×
291
        self.positions[:,2] += Decimal(z_shift)
×
292

293
    def shift_to_start_at_identity(self):
2✔
294
        """
295
        Alter the positions and orientations based so that the first pose 
296
        starts at Identity.
297
        """
298

299
        # Get pose of first robot position w.r.t world
300
        R_o = R.from_quat(self.orientations[0]).as_matrix()
2✔
301
        T_o = np.expand_dims(self.positions[0], axis=1)
2✔
302
        
303
        # Calculate the inverse (pose of world w.r.t first robot location)
304
        R_inv = R_o.T
2✔
305

306
        # Rotate positions and orientations
307
        self.positions = (R_inv @ (self.positions.T - T_o).astype(float)).T
2✔
308
        for i in range(self.len()):
2✔
309
            self.orientations[i] = R.from_matrix((R_inv @ R.from_quat(self.orientations[i]).as_matrix())).as_quat()
2✔
310

311
        # Convert back to decimal array
312
        self.positions = col_to_dec_arr(self.positions)
2✔
313
        self.orientations = col_to_dec_arr(self.orientations)
2✔
314

315
    def crop_data(self, start: Decimal, end: Decimal):
2✔
316
        """ Will crop the data so only values within [start, end] inclusive are kept. """
317

318
        # Create boolean mask of data to keep
319
        mask = (self.timestamps >= start) & (self.timestamps <= end)
2✔
320

321
        # Apply mask
322
        self.timestamps = self.timestamps[mask]
2✔
323
        self.positions = self.positions[mask]
2✔
324
        self.orientations = self.orientations[mask]
2✔
325

326
        # Empty poses as they might need to be recalculated
327
        self.poses = []
2✔
328

329
    # =========================================================================
330
    # ============================ Export Methods ============================= 
331
    # =========================================================================  
332

333
    @typechecked
2✔
334
    def to_csv(self, csv_path: Union[Path, str]):
2✔
335
        """
336
        Writes the odometry data to a .csv file. Note that data will be
337
        saved in the following order: timestamp, pos.x, pos.y, pos.z,
338
        ori.w, ori.x, ori.y, ori.z. Timestamp is in seconds.
339

340
        Args:
341
            csv_path (Path | str): Path to the output csv file.
342
            odom_topic (str): Topic of the Odometry messages.
343
        Returns:
344
            OdometryData: Instance of this class.
345
        """
346

347
        # setup tqdm 
348
        pbar = tqdm.tqdm(total=None, desc="Saving to csv... ", unit=" frames")
2✔
349

350
        # Check that file path doesn't already exist
351
        file_path = Path(csv_path)
2✔
352
        if os.path.exists(file_path):
2✔
353
            raise ValueError(f"Output file already exists: {file_path}")
×
354
        
355
        # Open csv file
356
        with open(file_path, 'w', newline='') as csvfile:
2✔
357
            writer = csv.writer(csvfile, delimiter=',')
2✔
358

359
            # Write the first row
360
            writer.writerow(['timestamp', 'x', 'y', 'z', 'qw', 'qx', 'qy', 'qz'])
2✔
361
                
362
            # Write message data to the csv file
363
            for i in range(len(self.timestamps)):
2✔
364
                writer.writerow([str(self.timestamps[i]), 
2✔
365
                    str(self.positions[i][0]), str(self.positions[i][1]), str(self.positions[i][2]),
366
                    str(self.orientations[i][3]), str(self.orientations[i][0]), str(self.orientations[i][1]), 
367
                    str(self.orientations[i][2])])
368
                pbar.update(1)
2✔
369

370
    # =========================================================================
371
    # =========================== Frame Conversions =========================== 
372
    # ========================================================================= 
373
    def to_FLU_frame(self):
2✔
374
        # If we are already in the FLU frame, return
375
        if self.frame == CoordinateFrame.FLU:
2✔
376
            print("Data already in FLU coordinate frame, returning...")
2✔
377
            return
2✔
378

379
        # If in NED, run the conversion
380
        elif self.frame == CoordinateFrame.NED:
2✔
381
            # Define the rotation matrix
382
            R_NED = np.array([[1,  0,  0],
2✔
383
                              [0, -1,  0],
384
                              [0,  0, -1]])
385

386
            # Do a change of basis to update the frame
387
            self._convert_frame(R_NED)
2✔
388

389
            # Update frame
390
            self.frame = CoordinateFrame.FLU
2✔
391

392
        # Otherwise, throw an error
393
        else:
394
            raise RuntimeError(f"OdometryData class is in an unexpected frame: {self.frame}!")
2✔
395
    
396
    @typechecked
2✔
397
    def _convert_frame(self, R_frame: np.ndarray):
2✔
398
        """ Uses a change of basis to update the positions and orientations. """
399
        R_frame_Q = R.from_matrix(R_frame)
2✔
400
        self.positions = (R_frame @ self.positions.T).T
2✔
401
        self._ori_change_of_basis(R_frame_Q)
2✔
402

403
    @typechecked
2✔
404
    def _ori_apply_rotation(self, R_i: R):
2✔
405
        """ Applies a rotation (not a change of basis) to orientations, thus stays in the same frame. """
406
        for i in range(self.len()):
2✔
407
            self.orientations[i] = (R_i * R.from_quat(self.orientations[i])).as_quat()
2✔
408

409
    @typechecked
2✔
410
    def _ori_change_of_basis(self, R_i: R):
2✔
411
        """ Applies a change of basis to orientations """
412
        for i in range(self.len()):
2✔
413
            self.orientations[i] = (R_i * R.from_quat(self.orientations[i]) * R_i.inv()).as_quat()
2✔
414

415
    # =========================================================================
416
    # =========================== Conversion to ROS =========================== 
417
    # ========================================================================= 
418

419
    @staticmethod
2✔
420
    def get_ros_msg_type(lib_type: ROSMsgLibType, msg_type: str = "Odometry") -> str:
2✔
421
        """ Return the __msgtype__ for an Imu msg. """
422
        if lib_type == ROSMsgLibType.ROSBAGS:
2✔
423
            typestore = get_typestore(Stores.ROS2_HUMBLE)
2✔
424
            if msg_type == "Odometry":
2✔
425
                return typestore.types['nav_msgs/msg/Odometry'].__msgtype__
2✔
426
            elif msg_type == "Path":
2✔
427
                return typestore.types['nav_msgs/msg/Path'].__msgtype__
2✔
428
            else:
NEW
429
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type}")
×
430
        else:
NEW
431
            raise NotImplementedError(f"Unsupported ROSMsgLibType {lib_type} for OdometryData.get_ros_msg_type()!")
×
432
    
433
    def _extract_seconds_and_nanoseconds(self, i: int):
2✔
434
        seconds = int(self.timestamps[i])
2✔
435
        nanoseconds = (self.timestamps[i] - self.timestamps[i].to_integral_value(rounding=decimal.ROUND_DOWN)) \
2✔
436
                        * Decimal("1e9").to_integral_value(decimal.ROUND_HALF_EVEN)
437
        return seconds, nanoseconds
2✔
438
    
439
    def get_ros_msg(self, lib_type: ROSMsgLibType, i: int, msg_type: str = "Odometry"):
2✔
440
        """
441
        Gets an Image ROS2 Humble message corresponding to the odometry in index i.
442
        
443
        Args:
444
            i (int): The index of the odometry data to convert.
445
        Raises:
446
            ValueError: If i is outside the data bounds.
447
        """
448

449
        # Check to make sure index is within data bounds
450
        if i < 0 or i >= self.len():
2✔
451
            raise IndexError(f"Index {i} is out of bounds!")
×
452
        
453
        # Extract seconds and nanoseconds
454
        seconds, nanoseconds = self._extract_seconds_and_nanoseconds(i)
2✔
455

456
        # Write the data into the new msg
457
        if lib_type == ROSMsgLibType.ROSBAGS:
2✔
458
            typestore = get_typestore(Stores.ROS2_HUMBLE)
2✔
459

460
            Odometry = typestore.types['nav_msgs/msg/Odometry']
2✔
461
            Header = typestore.types['std_msgs/msg/Header']
2✔
462
            Time = typestore.types['builtin_interfaces/msg/Time']
2✔
463
            PoseWithCovariance = typestore.types['geometry_msgs/msg/PoseWithCovariance']
2✔
464
            TwistWithCovariance = typestore.types['geometry_msgs/msg/TwistWithCovariance']
2✔
465
            Twist = typestore.types['geometry_msgs/msg/Twist']
2✔
466
            Vector3 = typestore.types['geometry_msgs/msg/Vector3']
2✔
467
            Path = typestore.types['nav_msgs/msg/Path']
2✔
468
            Pose = typestore.types['geometry_msgs/msg/Pose']
2✔
469
            Point = typestore.types['geometry_msgs/msg/Point']
2✔
470
            Quaternion = typestore.types['geometry_msgs/msg/Quaternion']
2✔
471

472
            if msg_type == "Odometry":
2✔
473
            
474
                return Odometry(Header(stamp=Time(sec=int(seconds), 
2✔
475
                                                nanosec=int(nanoseconds)), 
476
                                frame_id=self.frame_id),
477
                                child_frame_id=self.child_frame_id,
478
                                pose=PoseWithCovariance(pose=Pose(position=Point(x=self.positions[i][0],
479
                                                                    y=self.positions[i][1],
480
                                                                    z=self.positions[i][2]),
481
                                                        orientation=Quaternion(x=self.orientations[i][0],
482
                                                                                y=self.orientations[i][1],
483
                                                                                z=self.orientations[i][2],
484
                                                                                w=self.orientations[i][3])),
485
                                                        covariance=np.zeros(36)),
486
                                twist=TwistWithCovariance(twist=Twist(linear=Vector3(x=0, # Currently doesn't support Twist
487
                                                                                    y=0,
488
                                                                                    z=0,),
489
                                                                    angular=Vector3(x=0,
490
                                                                                    y=0,
491
                                                                                    z=0,)),
492
                                                        covariance=np.zeros(36)))
493
            elif msg_type == "Path":
2✔
494

495
                # Pre-calculate all the poses
496
                if len(self.poses) != self.len():
2✔
497
                    PoseStamped = typestore.types['geometry_msgs/msg/PoseStamped']
2✔
498

499
                    for j in range(self.len()):
2✔
500
                        seconds, nanoseconds = self._extract_seconds_and_nanoseconds(j)
2✔
501
                        self.poses.append(PoseStamped(Header(stamp=Time(sec=int(seconds), 
2✔
502
                                                                        nanosec=int(nanoseconds)),
503
                                                            frame_id=self.frame_id),
504
                                                    pose=Pose(position=Point(x=self.positions[j][0],
505
                                                                            y=self.positions[j][1],
506
                                                                            z=self.positions[j][2]),
507
                                    orientation=Quaternion(x=self.orientations[j][0],
508
                                                            y=self.orientations[j][1],
509
                                                            z=self.orientations[j][2],
510
                                                            w=self.orientations[j][3]))))
511

512
                return Path(Header(stamp=Time(sec=int(seconds), 
2✔
513
                                            nanosec=int(nanoseconds)),
514
                                frame_id=self.frame_id),
515
                                poses=self.poses[0:i+1:10])
516
            else:
NEW
517
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type} with ROSMsgLibType.ROSBAGS")
×
518
            
NEW
519
        elif lib_type == ROSMsgLibType.ROSPY:
×
NEW
520
            if msg_type == "maplab_msg/OdometryWithImuBiases":
×
521

NEW
522
                import rospy
×
NEW
523
                from maplab_msg.msg import OdometryWithImuBiases
×
NEW
524
                from geometry_msgs.msg import PoseWithCovariance, TwistWithCovariance, Point, Quaternion, Vector3
×
NEW
525
                from std_msgs.msg import Header
×
526

NEW
527
                msg = OdometryWithImuBiases()
×
NEW
528
                msg.header = Header()
×
NEW
529
                msg.header.stamp = rospy.Time(secs=seconds, nsecs=int(nanoseconds))
×
NEW
530
                msg.header.frame_id = self.frame_id
×
NEW
531
                msg.child_frame_id = self.child_frame_id
×
NEW
532
                msg.pose = PoseWithCovariance()
×
NEW
533
                msg.pose.pose.position = Point()
×
NEW
534
                msg.pose.pose.position.x = float(self.positions[i][0])
×
NEW
535
                msg.pose.pose.position.y = float(self.positions[i][1])
×
NEW
536
                msg.pose.pose.position.z = float(self.positions[i][2])
×
NEW
537
                msg.pose.pose.orientation = Quaternion()
×
NEW
538
                msg.pose.pose.orientation.x = float(self.orientations[i][0])
×
NEW
539
                msg.pose.pose.orientation.y = float(self.orientations[i][1])
×
NEW
540
                msg.pose.pose.orientation.z = float(self.orientations[i][2])
×
NEW
541
                msg.pose.pose.orientation.w = float(self.orientations[i][3])
×
NEW
542
                msg.pose.covariance = np.zeros(36)
×
NEW
543
                msg.twist = TwistWithCovariance()
×
NEW
544
                msg.twist.twist.linear = Vector3()
×
NEW
545
                msg.twist.twist.linear.x = 0.0  # NOTE: Currently doesn't support Twist
×
NEW
546
                msg.twist.twist.linear.y = 0.0
×
NEW
547
                msg.twist.twist.linear.z = 0.0
×
NEW
548
                msg.twist.twist.angular = Vector3()
×
NEW
549
                msg.twist.twist.angular.x = 0.0
×
NEW
550
                msg.twist.twist.angular.y = 0.0
×
NEW
551
                msg.twist.twist.angular.z = 0.0
×
NEW
552
                msg.twist.covariance = np.zeros(36)
×
NEW
553
                msg.accel_bias = Vector3() # NOTE: Assumes IMU biases are zero
×
NEW
554
                msg.accel_bias.x = 0.0
×
NEW
555
                msg.accel_bias.y = 0.0
×
NEW
556
                msg.accel_bias.z = 0.0
×
NEW
557
                msg.gyro_bias = Vector3()
×
NEW
558
                msg.gyro_bias.x = 0.0
×
NEW
559
                msg.gyro_bias.y = 0.0
×
NEW
560
                msg.gyro_bias.z = 0.0
×
NEW
561
                msg.odometry_state = 0 # Assumes default state
×
NEW
562
                return msg
×
563

564
            else:
NEW
565
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type} with ROSMsgLibType.ROSPY")
×
566
        else:
567
            raise NotImplementedError(f"Unsupported ROSMsgLibType {lib_type} for OdometryData.get_ros_msg()!")
×
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc