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

lunarlab-gatech / robotdataprocess / 20868268100

09 Jan 2026 11:10PM UTC coverage: 70.585% (-4.1%) from 74.672%
20868268100

Pull #10

github

DanielChaseButterfield
Remove tutrle import
Pull Request #10: (v0.2) Prototype code for ROS2 Publishing, and new ImageDataOnDisk class

508 of 747 new or added lines in 12 files covered. (68.01%)

3 existing lines in 2 files now uncovered.

1411 of 1999 relevant lines covered (70.59%)

1.41 hits per line

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

66.45
/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, Any
2✔
23
import tqdm
2✔
24

25
PATH_SLICE_STEP = 40
2✔
26

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

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

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

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

49
    # =========================================================================
50
    # ============================ Class Methods ============================== 
51
    # =========================================================================  
52

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

334
    # =========================================================================
335
    # ============================ Export Methods ============================= 
336
    # =========================================================================  
337

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

345
        Args:
346
            csv_path (Path | str): Path to the output csv file.
347
            odom_topic (str): Topic of the Odometry messages.
348
        Returns:
349
            OdometryData: Instance of this class.
350
        """
351

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

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

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

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

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

391
            # Do a change of basis to update the frame
392
            self._convert_frame(R_NED)
2✔
393

394
            # Update frame
395
            self.frame = CoordinateFrame.FLU
2✔
396

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

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

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

420
    # =========================================================================
421
    # =========================== Conversion to ROS =========================== 
422
    # ========================================================================= 
423

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

460
        # Check to make sure index is within data bounds
461
        if i < 0 or i >= self.len():
2✔
462
            raise IndexError(f"Index {i} is out of bounds!")
×
463
        
464
        # Extract seconds and nanoseconds
465
        seconds, nanoseconds = self._extract_seconds_and_nanoseconds(i)
2✔
466

467
        # Write the data into the new msg
468
        if lib_type == ROSMsgLibType.ROSBAGS:
2✔
469
            typestore = get_typestore(Stores.ROS2_HUMBLE)
2✔
470

471
            Odometry = typestore.types['nav_msgs/msg/Odometry']
2✔
472
            Header = typestore.types['std_msgs/msg/Header']
2✔
473
            Time = typestore.types['builtin_interfaces/msg/Time']
2✔
474
            PoseWithCovariance = typestore.types['geometry_msgs/msg/PoseWithCovariance']
2✔
475
            TwistWithCovariance = typestore.types['geometry_msgs/msg/TwistWithCovariance']
2✔
476
            Twist = typestore.types['geometry_msgs/msg/Twist']
2✔
477
            Vector3 = typestore.types['geometry_msgs/msg/Vector3']
2✔
478
            Path = typestore.types['nav_msgs/msg/Path']
2✔
479
            Pose = typestore.types['geometry_msgs/msg/Pose']
2✔
480
            Point = typestore.types['geometry_msgs/msg/Point']
2✔
481
            Quaternion = typestore.types['geometry_msgs/msg/Quaternion']
2✔
482

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

506
                # Pre-calculate all the poses
507
                if len(self.poses) != self.len():
2✔
508
                    PoseStamped = typestore.types['geometry_msgs/msg/PoseStamped']
2✔
509

510
                    for j in range(self.len()):
2✔
511
                        sec, nanosec = self._extract_seconds_and_nanoseconds(j)
2✔
512
                        self.poses.append(PoseStamped(Header(stamp=Time(sec=int(sec), 
2✔
513
                                                                        nanosec=int(nanosec)),
514
                                                            frame_id=self.frame_id),
515
                                                    pose=Pose(position=Point(x=self.positions[j][0],
516
                                                                            y=self.positions[j][1],
517
                                                                            z=self.positions[j][2]),
518
                                    orientation=Quaternion(x=self.orientations[j][0],
519
                                                            y=self.orientations[j][1],
520
                                                            z=self.orientations[j][2],
521
                                                            w=self.orientations[j][3]))))
522

523
                return Path(Header(stamp=Time(sec=int(seconds), 
2✔
524
                                            nanosec=int(nanoseconds)),
525
                                frame_id=self.frame_id),
526
                                poses=self.poses[0:i+1:PATH_SLICE_STEP])
527
            else:
NEW
528
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type} with ROSMsgLibType.ROSBAGS")
×
529
            
NEW
530
        elif lib_type == ROSMsgLibType.ROSPY:
×
NEW
531
            if msg_type == "maplab_msg/OdometryWithImuBiases":
×
532

NEW
533
                import rospy
×
NEW
534
                from maplab_msg.msg import OdometryWithImuBiases
×
NEW
535
                from geometry_msgs.msg import PoseWithCovariance, TwistWithCovariance, Point, Quaternion, Vector3
×
NEW
536
                from std_msgs.msg import Header
×
537

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

575
            else:
NEW
576
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type} with ROSMsgLibType.ROSPY")
×
577
        
NEW
578
        elif lib_type == ROSMsgLibType.RCLPY:
×
NEW
579
            if msg_type == "Path":
×
580
                
NEW
581
                from builtin_interfaces.msg import Time
×
NEW
582
                from nav_msgs.msg import Path
×
NEW
583
                from std_msgs.msg import Header
×
584

585
                # Pre-calculate all the poses
NEW
586
                if len(self.poses_rclpy) != self.len():
×
587

NEW
588
                    from geometry_msgs.msg import PoseStamped, Pose, Point, Quaternion
×
589

NEW
590
                    for j in range(self.len()):
×
NEW
591
                        sec, nanosec = self._extract_seconds_and_nanoseconds(j)
×
NEW
592
                        pose_msg = PoseStamped()
×
NEW
593
                        pose_msg.header = Header()
×
NEW
594
                        pose_msg.header.stamp = Time(sec=int(sec), nanosec=int(nanosec))
×
NEW
595
                        pose_msg.header.frame_id = self.frame_id
×
NEW
596
                        pose_msg.pose = Pose()
×
NEW
597
                        pose_msg.pose.position = Point()
×
NEW
598
                        pose_msg.pose.position.x = float(self.positions[j][0])
×
NEW
599
                        pose_msg.pose.position.y = float(self.positions[j][1])
×
NEW
600
                        pose_msg.pose.position.z = float(self.positions[j][2])
×
NEW
601
                        pose_msg.pose.orientation = Quaternion()
×
NEW
602
                        pose_msg.pose.orientation.x = float(self.orientations[j][0])
×
NEW
603
                        pose_msg.pose.orientation.y = float(self.orientations[j][1])
×
NEW
604
                        pose_msg.pose.orientation.z = float(self.orientations[j][2])
×
NEW
605
                        pose_msg.pose.orientation.w = float(self.orientations[j][3])
×
NEW
606
                        self.poses_rclpy.append(pose_msg)
×
607

NEW
608
                msg = Path()
×
NEW
609
                msg.header = Header()
×
NEW
610
                msg.header.stamp = Time(sec=int(seconds), nanosec=int(nanoseconds))
×
NEW
611
                msg.header.frame_id = self.frame_id
×
NEW
612
                msg.poses = self.poses_rclpy[0:i+1:PATH_SLICE_STEP]
×
NEW
613
                return msg
×
614
            
615
            else:
NEW
616
                raise ValueError(f"Unsupported msg_type for OdometryData: {msg_type} with ROSMsgLibType.RCLPY")
×
617
        else:
618
            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