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

lunarlab-gatech / robotdataprocess / 21222003393

21 Jan 2026 06:58PM UTC coverage: 78.695% (+4.0%) from 74.672%
21222003393

Pull #10

github

DanielChaseButterfield
test_RosPublisher.py test case for OdometryData
Pull Request #10: (v0.2) Prototype code for ROS2 Publishing, and new ImageDataOnDisk class

843 of 1123 new or added lines in 13 files covered. (75.07%)

3 existing lines in 2 files now uncovered.

1725 of 2192 relevant lines covered (78.7%)

1.57 hits per line

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

75.69
/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
from ..ModuleImporter import ModuleImporter
2✔
11
import numpy as np
2✔
12
from numpy.typing import NDArray
2✔
13
import os
2✔
14
import pandas as pd
2✔
15
from .PathData import PathData
2✔
16
from pathlib import Path
2✔
17
from ..ros.Ros2BagWrapper import Ros2BagWrapper
2✔
18
from rosbags.rosbag2 import Reader as Reader2
2✔
19
from rosbags.typesys import Stores, get_typestore
2✔
20
from rosbags.typesys.store import Typestore
2✔
21
from scipy.spatial.transform import Rotation as R
2✔
22
from typeguard import typechecked
2✔
23
from typing import Union, List, Tuple, Any
2✔
24
import tqdm
2✔
25

26
PATH_SLICE_STEP = 40
2✔
27

28
@typechecked
2✔
29
class OdometryData(PathData):
2✔
30

31
    # Define odometry-specific data attributes
32
    child_frame_id: str
2✔
33
    poses: list # Saved nav_msgs/msg/Pose for rosbags
2✔
34
    poses_rclpy: list # Saved nav_msgs/msg/Pose for rclpy
2✔
35

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

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

50
    # =========================================================================
51
    # ============================ Class Methods ============================== 
52
    # =========================================================================  
53

54
    @classmethod
2✔
55
    @typechecked
2✔
56
    def from_ros2_bag(cls, bag_path: Union[Path, str], odom_topic: str, frame: CoordinateFrame):
2✔
57
        """
58
        Creates a class structure from a ROS2 bag file with an Odometry topic.
59

60
        Args:
61
            bag_path (Path | str): Path to the ROS2 bag file.
62
            odom_topic (str): Topic of the Odometry messages.
63
        Returns:
64
            OdometryData: Instance of this class.
65
        """
66

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

77
        # Setup tqdm bar & counter
78
        pbar = tqdm.tqdm(total=num_msgs, desc="Extracting Odometry...", unit=" msgs")
2✔
79
        i = 0
2✔
80

81
        # Extract the odometry information
82
        frame_id, child_frame_id = None, None
2✔
83
        with Reader2(str(bag_path)) as reader:
2✔
84

85
            # Extract frames from first message
86
            connections = [x for x in reader.connections if x.topic == odom_topic]
2✔
87
            for conn, timestamp, rawdata in reader.messages(connections=connections):  
2✔
88
                msg = typestore.deserialize_cdr(rawdata, conn.msgtype)
2✔
89
                frame_id = msg.header.frame_id
2✔
90
                child_frame_id = msg.child_frame_id
2✔
91
                break
2✔
92

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

104
                # NOTE: Doesn't support Twist information currently
105

106
                # Increment the count
107
                i += 1
2✔
108
                pbar.update(1)
2✔
109

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

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

140
        Returns:
141
            OdometryData: Instance of this class.
142
        """
143

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

152
        # Read the csv file
153
        header = 0 if header_included else None
2✔
154
        df1 = pd.read_csv(str(csv_path), header=header, index_col=False, sep=separator, engine='python')
2✔
155

156
        # Rename columns to standard names
157
        rename_dict = {}
2✔
158
        desired_data = ['timestamp', 'x', 'y', 'z', 'qw', 'qx', 'qy', 'qz']
2✔
159
        for j, ind in enumerate(column_to_data):
2✔
160
            rename_dict[df1.columns[ind]] = desired_data[j]
2✔
161
        df1 = df1.rename(columns=rename_dict)
2✔
162

163
        # Using the filter if provided, remove unwanted rows
164
        if filter is not None:
2✔
165
            df1 = df1[df1[filter[0]] == filter[1]]
2✔
166

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

178
        # Reorder the data if needed
179
        if reorder_data:
2✔
NEW
180
            print("Warning: This code is not tested yet!")
×
NEW
181
            sort_indices = np.argsort(timestamps_np)
×
NEW
182
            timestamps_np = timestamps_np[sort_indices]
×
NEW
183
            positions_np = positions_np[sort_indices]
×
NEW
184
            orientations_np = orientations_np[sort_indices]
×
185

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

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

219
        # Count the number of lines in the file
220
        line_count = 0
2✔
221
        with open(str(file_path), 'r') as file:
2✔
222
            for _ in file: 
2✔
223
                line_count += 1
2✔
224

225
        # Setup arrays to hold data
226
        timestamps_np = np.zeros((line_count), dtype=object)
2✔
227
        positions_np = np.zeros((line_count, 3), dtype=object)
2✔
228
        orientations_np = np.zeros((line_count, 4), dtype=object)
2✔
229

230
        # Open the txt file and read in the data
231
        with open(str(file_path), 'r') as file:
2✔
232
            for i, line in enumerate(file):
2✔
233
                line_split = line.split(' ')
2✔
234
                timestamps_np[i] = line_split[column_to_data[0]]
2✔
235
                positions_np[i] = np.array([line_split[column_to_data[1]], line_split[column_to_data[2]], line_split[column_to_data[3]]])
2✔
236
                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✔
237

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

260
        Args:
261
            xy_noise_std_per_frame (float): Standard deviation of the gaussian 
262
                distribution for xy, whose output is then run through abs().
263
            z_noise_std_per_frame (float): Same as above, but for z.
264
        """
265

266
        # Track cumulative noise for each field
267
        cumulative_noise_pos = {'x': 0.0, 'y': 0.0, 'z': 0.0}
×
268

269
        # For each position
270
        for i in range(len(self.timestamps)):
×
271

272
            # Sample noise and accumulate
273
            noise_pos = {'x': np.random.normal(0, xy_noise_std_per_frame),
×
274
                        'y': np.random.normal(0, xy_noise_std_per_frame),
275
                        'z': np.random.normal(0, z_noise_std_per_frame)}
276
            for key in cumulative_noise_pos:
×
277
                cumulative_noise_pos[key] += abs(noise_pos[key])
×
278

279
            # Update positions
280
            self.positions[i][0] += Decimal(cumulative_noise_pos['x'])
×
281
            self.positions[i][1] += Decimal(cumulative_noise_pos['y'])
×
282
            self.positions[i][2] += Decimal(cumulative_noise_pos['z'])
×
283

284
    @typechecked
2✔
285
    def shift_position(self, x_shift: float, y_shift: float, z_shift: float):
2✔
286
        """
287
        Shifts the positions of the odometry.
288

289
        Args:
290
            x_shift (float): Shift in x-axis.
291
            y_shift (float): Shift in y_axis.
292
            z_shift (float): Shift in z_axis.
293
        """
294
        self.positions[:,0] += Decimal(x_shift)
×
295
        self.positions[:,1] += Decimal(y_shift)
×
296
        self.positions[:,2] += Decimal(z_shift)
×
297

298
    def shift_to_start_at_identity(self):
2✔
299
        """
300
        Alter the positions and orientations based so that the first pose 
301
        starts at Identity.
302
        """
303

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

311
        # Rotate positions and orientations
312
        self.positions = (R_inv @ (self.positions.T - T_o).astype(float)).T
2✔
313
        for i in range(self.len()):
2✔
314
            self.orientations[i] = R.from_matrix((R_inv @ R.from_quat(self.orientations[i]).as_matrix())).as_quat()
2✔
315

316
        # Convert back to decimal array
317
        self.positions = col_to_dec_arr(self.positions)
2✔
318
        self.orientations = col_to_dec_arr(self.orientations)
2✔
319

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

323
        # Create boolean mask of data to keep
324
        mask = (self.timestamps >= start) & (self.timestamps <= end)
2✔
325

326
        # Apply mask
327
        self.timestamps = self.timestamps[mask]
2✔
328
        self.positions = self.positions[mask]
2✔
329
        self.orientations = self.orientations[mask]
2✔
330

331
        # Empty poses as they might need to be recalculated
332
        self.poses = []
2✔
333
        self.poses_rclpy = []
2✔
334

335
    # =========================================================================
336
    # ============================ Export Methods ============================= 
337
    # =========================================================================  
338

339
    @typechecked
2✔
340
    def to_csv(self, csv_path: Union[Path, str], write_header: bool = True):
2✔
341
        """
342
        Writes the odometry data to a .csv file. Note that data will be
343
        saved in the following order: timestamp, pos.x, pos.y, pos.z,
344
        ori.w, ori.x, ori.y, ori.z. Timestamp is in seconds.
345

346
        Args:
347
            csv_path (Path | str): Path to the output csv file.
348
            odom_topic (str): Topic of the Odometry messages.
349
            write_header (bool): If false, skip the header row.
350
        Returns:
351
            OdometryData: Instance of this class.
352
        """
353

354
        # setup tqdm 
355
        pbar = tqdm.tqdm(total=None, desc="Saving to csv... ", unit=" frames")
2✔
356

357
        # Check that file path doesn't already exist
358
        file_path = Path(csv_path)
2✔
359
        if os.path.exists(file_path):
2✔
360
            raise ValueError(f"Output file already exists: {file_path}")
×
361
        
362
        # Open csv file
363
        with open(file_path, 'w', newline='') as csvfile:
2✔
364
            writer = csv.writer(csvfile, delimiter=',')
2✔
365

366
            # Write the first row
367
            if write_header:
2✔
368
                writer.writerow(['timestamp', 'x', 'y', 'z', 'qw', 'qx', 'qy', 'qz'])
2✔
369
                
370
            # Write message data to the csv file
371
            for i in range(len(self.timestamps)):
2✔
372
                writer.writerow([str(self.timestamps[i]), 
2✔
373
                    str(self.positions[i][0]), str(self.positions[i][1]), str(self.positions[i][2]),
374
                    str(self.orientations[i][3]), str(self.orientations[i][0]), str(self.orientations[i][1]), 
375
                    str(self.orientations[i][2])])
376
                pbar.update(1)
2✔
377

378
    # =========================================================================
379
    # =========================== Frame Conversions =========================== 
380
    # ========================================================================= 
381
    def to_FLU_frame(self):
2✔
382
        # If we are already in the FLU frame, return
383
        if self.frame == CoordinateFrame.FLU:
2✔
384
            print("Data already in FLU coordinate frame, returning...")
2✔
385
            return
2✔
386

387
        # If in NED, run the conversion
388
        elif self.frame == CoordinateFrame.NED:
2✔
389
            # Define the rotation matrix
390
            R_NED = np.array([[1,  0,  0],
2✔
391
                              [0, -1,  0],
392
                              [0,  0, -1]])
393

394
            # Do a change of basis to update the frame
395
            self._convert_frame(R_NED)
2✔
396

397
            # Update frame
398
            self.frame = CoordinateFrame.FLU
2✔
399

400
        # Otherwise, throw an error
401
        else:
402
            raise RuntimeError(f"OdometryData class is in an unexpected frame: {self.frame}!")
2✔
403
    
404
    @typechecked
2✔
405
    def _convert_frame(self, R_frame: np.ndarray):
2✔
406
        """ Uses a change of basis to update the positions and orientations. """
407
        R_frame_Q = R.from_matrix(R_frame)
2✔
408
        self.positions = (R_frame @ self.positions.T).T
2✔
409
        self._ori_change_of_basis(R_frame_Q)
2✔
410

411
    @typechecked
2✔
412
    def _ori_apply_rotation(self, R_i: R):
2✔
413
        """ Applies a rotation (not a change of basis) to orientations, thus stays in the same frame. """
414
        for i in range(self.len()):
2✔
415
            self.orientations[i] = (R_i * R.from_quat(self.orientations[i])).as_quat()
2✔
416

417
    @typechecked
2✔
418
    def _ori_change_of_basis(self, R_i: R):
2✔
419
        """ Applies a change of basis to orientations """
420
        for i in range(self.len()):
2✔
421
            self.orientations[i] = (R_i * R.from_quat(self.orientations[i]) * R_i.inv()).as_quat()
2✔
422

423
    # =========================================================================
424
    # =========================== Conversion to ROS =========================== 
425
    # ========================================================================= 
426

427
    @staticmethod
2✔
428
    def get_ros_msg_type(lib_type: ROSMsgLibType, msg_type: str = "Odometry") -> Any:
2✔
429
        """ Return the __msgtype__ for an Odometry msg. """
430
        if lib_type == ROSMsgLibType.ROSBAGS:
2✔
431
            typestore = get_typestore(Stores.ROS2_HUMBLE)
2✔
432
            if msg_type == "Odometry":
2✔
433
                return typestore.types['nav_msgs/msg/Odometry'].__msgtype__
2✔
434
            elif msg_type == "Path":
2✔
435
                return typestore.types['nav_msgs/msg/Path'].__msgtype__
2✔
436
            else:
NEW
437
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type}")
×
438
        elif lib_type == ROSMsgLibType.RCLPY:
2✔
439
            if msg_type == "Path":
2✔
440
                return ModuleImporter.get_module_attribute('nav_msgs.msg', 'Path')
2✔
441
            else:
NEW
442
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type}")
×
NEW
443
        elif lib_type == ROSMsgLibType.ROSPY:
×
NEW
444
            if msg_type == "maplab_msg/OdometryWithImuBiases":
×
NEW
445
                return ModuleImporter.get_module_attribute('maplab_msgs.msg', 'OdometryWithImuBiases')
×
NEW
446
            elif msg_type == "Path":
×
NEW
447
                return ModuleImporter.get_module_attribute('nav_msgs.msg', 'Path')
×
448
            else:
NEW
449
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type}")
×
450
        else:
NEW
451
            raise NotImplementedError(f"Unsupported ROSMsgLibType {lib_type} for OdometryData.get_ros_msg_type()!")
×
452
    
453
    def _extract_seconds_and_nanoseconds(self, i: int):
2✔
454
        seconds = int(self.timestamps[i])
2✔
455
        nanoseconds = (self.timestamps[i] - self.timestamps[i].to_integral_value(rounding=decimal.ROUND_DOWN)) \
2✔
456
                        * Decimal("1e9").to_integral_value(decimal.ROUND_HALF_EVEN)
457
        return seconds, nanoseconds
2✔
458
    
459
    def get_ros_msg(self, lib_type: ROSMsgLibType, i: int, msg_type: str = "Odometry"):
2✔
460
        """
461
        Gets an Image ROS2 Humble message corresponding to the odometry in index i.
462
        
463
        Args:
464
            i (int): The index of the odometry data to convert.
465
        Raises:
466
            ValueError: If i is outside the data bounds.
467
        """
468

469
        # Check to make sure index is within data bounds
470
        if i < 0 or i >= self.len():
2✔
471
            raise IndexError(f"Index {i} is out of bounds!")
×
472
        
473
        # Extract seconds and nanoseconds
474
        seconds, nanoseconds = self._extract_seconds_and_nanoseconds(i)
2✔
475

476
        # Write the data into the new msg
477
        if lib_type == ROSMsgLibType.ROSBAGS:
2✔
478
            typestore = get_typestore(Stores.ROS2_HUMBLE)
2✔
479

480
            Odometry = typestore.types['nav_msgs/msg/Odometry']
2✔
481
            Header = typestore.types['std_msgs/msg/Header']
2✔
482
            Time = typestore.types['builtin_interfaces/msg/Time']
2✔
483
            PoseWithCovariance = typestore.types['geometry_msgs/msg/PoseWithCovariance']
2✔
484
            TwistWithCovariance = typestore.types['geometry_msgs/msg/TwistWithCovariance']
2✔
485
            Twist = typestore.types['geometry_msgs/msg/Twist']
2✔
486
            Vector3 = typestore.types['geometry_msgs/msg/Vector3']
2✔
487
            Path = typestore.types['nav_msgs/msg/Path']
2✔
488
            Pose = typestore.types['geometry_msgs/msg/Pose']
2✔
489
            Point = typestore.types['geometry_msgs/msg/Point']
2✔
490
            Quaternion = typestore.types['geometry_msgs/msg/Quaternion']
2✔
491

492
            if msg_type == "Odometry":
2✔
493
            
494
                return Odometry(Header(stamp=Time(sec=int(seconds), 
2✔
495
                                                nanosec=int(nanoseconds)), 
496
                                frame_id=self.frame_id),
497
                                child_frame_id=self.child_frame_id,
498
                                pose=PoseWithCovariance(pose=Pose(position=Point(x=self.positions[i][0],
499
                                                                    y=self.positions[i][1],
500
                                                                    z=self.positions[i][2]),
501
                                                        orientation=Quaternion(x=self.orientations[i][0],
502
                                                                                y=self.orientations[i][1],
503
                                                                                z=self.orientations[i][2],
504
                                                                                w=self.orientations[i][3])),
505
                                                        covariance=np.zeros(36)),
506
                                twist=TwistWithCovariance(twist=Twist(linear=Vector3(x=0, # Currently doesn't support Twist
507
                                                                                    y=0,
508
                                                                                    z=0,),
509
                                                                    angular=Vector3(x=0,
510
                                                                                    y=0,
511
                                                                                    z=0,)),
512
                                                        covariance=np.zeros(36)))
513
            elif msg_type == "Path":
2✔
514

515
                # Pre-calculate all the poses
516
                if len(self.poses) != self.len():
2✔
517
                    PoseStamped = typestore.types['geometry_msgs/msg/PoseStamped']
2✔
518

519
                    for j in range(self.len()):
2✔
520
                        sec, nanosec = self._extract_seconds_and_nanoseconds(j)
2✔
521
                        self.poses.append(PoseStamped(Header(stamp=Time(sec=int(sec), 
2✔
522
                                                                        nanosec=int(nanosec)),
523
                                                            frame_id=self.frame_id),
524
                                                    pose=Pose(position=Point(x=self.positions[j][0],
525
                                                                            y=self.positions[j][1],
526
                                                                            z=self.positions[j][2]),
527
                                    orientation=Quaternion(x=self.orientations[j][0],
528
                                                            y=self.orientations[j][1],
529
                                                            z=self.orientations[j][2],
530
                                                            w=self.orientations[j][3]))))
531

532
                return Path(Header(stamp=Time(sec=int(seconds), 
2✔
533
                                            nanosec=int(nanoseconds)),
534
                                frame_id=self.frame_id),
535
                                poses=self.poses[0:i+1:PATH_SLICE_STEP])
536
            else:
NEW
537
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type} with ROSMsgLibType.ROSBAGS")
×
538
            
539
        elif lib_type == ROSMsgLibType.ROSPY or lib_type == ROSMsgLibType.RCLPY:
2✔
540
            if msg_type == "maplab_msg/OdometryWithImuBiases":
2✔
541
                
NEW
542
                if lib_type == ROSMsgLibType.RCLPY:
×
NEW
543
                    raise ValueError("maplab_msg/OdometryWithImuBiases is not supported for RCLPY!")
×
544

NEW
545
                rospy = ModuleImporter.get_module('rospy')
×
NEW
546
                OdometryWithImuBiases = ModuleImporter.get_module_attribute('maplab_msgs.msg', 'OdometryWithImuBiases')
×
NEW
547
                PoseWithCovariance = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'PoseWithCovariance')
×
NEW
548
                TwistWithCovariance = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'TwistWithCovariance')
×
NEW
549
                Point = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'Point')
×
NEW
550
                Quaternion = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'Quaternion')
×
NEW
551
                Vector3 = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'Vector3')
×
NEW
552
                Header = ModuleImporter.get_module_attribute('std_msgs.msg', 'Header')
×
553

NEW
554
                msg = OdometryWithImuBiases()
×
NEW
555
                msg.header = Header()
×
NEW
556
                msg.header.stamp = rospy.Time(secs=seconds, nsecs=int(nanoseconds))
×
NEW
557
                msg.header.frame_id = self.frame_id
×
NEW
558
                msg.child_frame_id = self.child_frame_id
×
NEW
559
                msg.pose = PoseWithCovariance()
×
NEW
560
                msg.pose.pose.position = Point()
×
NEW
561
                msg.pose.pose.position.x = float(self.positions[i][0])
×
NEW
562
                msg.pose.pose.position.y = float(self.positions[i][1])
×
NEW
563
                msg.pose.pose.position.z = float(self.positions[i][2])
×
NEW
564
                msg.pose.pose.orientation = Quaternion()
×
NEW
565
                msg.pose.pose.orientation.x = float(self.orientations[i][0])
×
NEW
566
                msg.pose.pose.orientation.y = float(self.orientations[i][1])
×
NEW
567
                msg.pose.pose.orientation.z = float(self.orientations[i][2])
×
NEW
568
                msg.pose.pose.orientation.w = float(self.orientations[i][3])
×
NEW
569
                msg.pose.covariance = np.zeros(36) # NOTE: Assumes covariance of zero.
×
NEW
570
                msg.twist = TwistWithCovariance()
×
NEW
571
                msg.twist.twist.linear = Vector3()
×
NEW
572
                msg.twist.twist.linear.x = 0.0  # NOTE: Currently doesn't support Twist
×
NEW
573
                msg.twist.twist.linear.y = 0.0
×
NEW
574
                msg.twist.twist.linear.z = 0.0
×
NEW
575
                msg.twist.twist.angular = Vector3()
×
NEW
576
                msg.twist.twist.angular.x = 0.0
×
NEW
577
                msg.twist.twist.angular.y = 0.0
×
NEW
578
                msg.twist.twist.angular.z = 0.0
×
NEW
579
                msg.twist.covariance = np.zeros(36)
×
NEW
580
                msg.accel_bias = Vector3() # NOTE: Assumes IMU biases are zero
×
NEW
581
                msg.accel_bias.x = 0.0
×
NEW
582
                msg.accel_bias.y = 0.0
×
NEW
583
                msg.accel_bias.z = 0.0
×
NEW
584
                msg.gyro_bias = Vector3()
×
NEW
585
                msg.gyro_bias.x = 0.0
×
NEW
586
                msg.gyro_bias.y = 0.0
×
NEW
587
                msg.gyro_bias.z = 0.0
×
NEW
588
                msg.odometry_state = 0 # NOTE: Assumes default state
×
NEW
589
                return msg
×
590

591
            elif msg_type == "Path":
2✔
592
                
593
                Path = ModuleImporter.get_module_attribute('nav_msgs.msg', 'Path')
2✔
594
                Header = ModuleImporter.get_module_attribute('std_msgs.msg', 'Header')
2✔
595

596
                # Pre-calculate all the poses
597
                if len(self.poses_rclpy) != self.len():
2✔
598

599
                    PoseStamped = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'PoseStamped')
2✔
600
                    Pose = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'Pose')
2✔
601
                    Point = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'Point')
2✔
602
                    Quaternion = ModuleImporter.get_module_attribute('geometry_msgs.msg', 'Quaternion')
2✔
603

604
                    for j in range(self.len()):
2✔
605
                        sec, nanosec = self._extract_seconds_and_nanoseconds(j)
2✔
606
                        pose_msg = PoseStamped()
2✔
607
                        pose_msg.header = Header()
2✔
608
                        if lib_type == ROSMsgLibType.RCLPY:
2✔
609
                            Time = ModuleImporter.get_module_attribute('rclpy.time', 'Time')
2✔
610
                            pose_msg.header.stamp = Time(seconds=seconds, nanoseconds=int(nanoseconds)).to_msg()
2✔
611
                        else:
NEW
612
                            rospy = ModuleImporter.get_module('rospy')
×
NEW
613
                            pose_msg.header.stamp = rospy.Time(secs=int(seconds), nsecs=int(nanoseconds))
×
614
                        pose_msg.header.frame_id = self.frame_id
2✔
615
                        pose_msg.pose = Pose()
2✔
616
                        pose_msg.pose.position = Point()
2✔
617
                        pose_msg.pose.position.x = float(self.positions[j][0])
2✔
618
                        pose_msg.pose.position.y = float(self.positions[j][1])
2✔
619
                        pose_msg.pose.position.z = float(self.positions[j][2])
2✔
620
                        pose_msg.pose.orientation = Quaternion()
2✔
621
                        pose_msg.pose.orientation.x = float(self.orientations[j][0])
2✔
622
                        pose_msg.pose.orientation.y = float(self.orientations[j][1])
2✔
623
                        pose_msg.pose.orientation.z = float(self.orientations[j][2])
2✔
624
                        pose_msg.pose.orientation.w = float(self.orientations[j][3])
2✔
625
                        self.poses_rclpy.append(pose_msg)
2✔
626

627
                msg = Path()
2✔
628
                msg.header = Header()
2✔
629
                if lib_type == ROSMsgLibType.RCLPY:
2✔
630
                    Time = ModuleImporter.get_module_attribute('rclpy.time', 'Time')
2✔
631
                    msg.header.stamp = Time(seconds=seconds, nanoseconds=int(nanoseconds)).to_msg()
2✔
632
                else:
NEW
633
                    rospy = ModuleImporter.get_module('rospy')
×
NEW
634
                    msg.header.stamp = rospy.Time(secs=int(seconds), nsecs=int(nanoseconds))
×
635
                msg.header.frame_id = self.frame_id
2✔
636
                msg.poses = self.poses_rclpy[0:i+1:PATH_SLICE_STEP]
2✔
637
                return msg
2✔
638
            
639
            else:
NEW
640
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type} with ROSMsgLibType.ROSPY or ROSMsgLibType.RCLPY.")
×
641
        else:
642
            raise NotImplementedError(f"Unsupported ROSMsgLibType {lib_type} for OdometryData.get_ros_msg()!")
2✔
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