Handle trace without lifecycle transitions (#28)
Signed-off-by: Christophe Bedard <christophe.bedard@apex.ai>
This commit is contained in:
parent
d8c352c082
commit
6550e878bc
2 changed files with 13 additions and 3 deletions
|
@ -39,3 +39,9 @@ class TestUtils(unittest.TestCase):
|
||||||
data_model.finalize()
|
data_model.finalize()
|
||||||
util = Ros2DataModelUtil(data_model)
|
util = Ros2DataModelUtil(data_model)
|
||||||
self.assertEqual({}, util.get_callback_symbols())
|
self.assertEqual({}, util.get_callback_symbols())
|
||||||
|
|
||||||
|
def test_ros2_no_lifecycle_transitions(self) -> None:
|
||||||
|
data_model = Ros2DataModel()
|
||||||
|
data_model.finalize()
|
||||||
|
util = Ros2DataModelUtil(data_model)
|
||||||
|
self.assertEqual({}, util.get_lifecycle_node_state_intervals())
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
"""Module for ROS data model utils."""
|
"""Module for ROS data model utils."""
|
||||||
|
|
||||||
from typing import Any
|
from typing import Any
|
||||||
|
from typing import Dict
|
||||||
from typing import List
|
from typing import List
|
||||||
from typing import Mapping
|
from typing import Mapping
|
||||||
from typing import Optional
|
from typing import Optional
|
||||||
|
@ -117,7 +118,7 @@ class Ros2DataModelUtil(DataModelUtil):
|
||||||
callback_instances = self.data.callback_instances
|
callback_instances = self.data.callback_instances
|
||||||
callback_symbols = self.data.callback_symbols
|
callback_symbols = self.data.callback_symbols
|
||||||
|
|
||||||
if 'callback_object' not in callback_instances.columns:
|
if callback_instances.empty:
|
||||||
return {}
|
return {}
|
||||||
|
|
||||||
# Get a list of callback objects
|
# Get a list of callback objects
|
||||||
|
@ -507,7 +508,7 @@ class Ros2DataModelUtil(DataModelUtil):
|
||||||
|
|
||||||
def get_lifecycle_node_state_intervals(
|
def get_lifecycle_node_state_intervals(
|
||||||
self,
|
self,
|
||||||
) -> DataFrame:
|
) -> Dict[int, DataFrame]:
|
||||||
"""
|
"""
|
||||||
Get state intervals (start, end) for all lifecycle nodes.
|
Get state intervals (start, end) for all lifecycle nodes.
|
||||||
|
|
||||||
|
@ -522,8 +523,11 @@ class Ros2DataModelUtil(DataModelUtil):
|
||||||
:return: dictionary with a dataframe (with each row containing state interval information)
|
:return: dictionary with a dataframe (with each row containing state interval information)
|
||||||
for each lifecycle node
|
for each lifecycle node
|
||||||
"""
|
"""
|
||||||
data = {}
|
|
||||||
lifecycle_transitions = self.data.lifecycle_transitions.copy()
|
lifecycle_transitions = self.data.lifecycle_transitions.copy()
|
||||||
|
if lifecycle_transitions.empty:
|
||||||
|
return {}
|
||||||
|
|
||||||
|
data = {}
|
||||||
state_machine_handles = set(lifecycle_transitions['state_machine_handle'])
|
state_machine_handles = set(lifecycle_transitions['state_machine_handle'])
|
||||||
for state_machine_handle in state_machine_handles:
|
for state_machine_handle in state_machine_handles:
|
||||||
transitions = lifecycle_transitions.loc[
|
transitions = lifecycle_transitions.loc[
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue