Skip to content

Commit cbe0647

Browse files
leander-dsouzaSakshayMahna
authored andcommitted
Configure the entire nav2 stack with mypy (ros-navigation#5084)
* Configured tools to be mypy compliant. Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> * Added mypy as a pre-commit hook. Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> * Simplified workflow by including all packages with mypy. Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> --------- Signed-off-by: Leander Stephen D'Souza <leanderdsouza1234@gmail.com> Signed-off-by: Sakshay Mahna <sakshum19@gmail.com>
1 parent 2245c49 commit cbe0647

File tree

11 files changed

+146
-110
lines changed

11 files changed

+146
-110
lines changed

.github/workflows/lint.yml

Lines changed: 7 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -11,43 +11,20 @@ jobs:
1111
strategy:
1212
fail-fast: false
1313
matrix:
14-
linter: [xmllint, cpplint, uncrustify, pep257, flake8]
14+
linter: [xmllint, cpplint, uncrustify, pep257, flake8, mypy]
1515
steps:
1616
- uses: actions/checkout@v4
17-
- uses: ros-tooling/action-ros-lint@v0.1
18-
with:
19-
linter: ${{ matrix.linter }}
20-
distribution: rolling
21-
package-name: "*"
2217

23-
ament_lint_mypy:
24-
name: ament_mypy
25-
runs-on: ubuntu-latest
26-
container:
27-
image: rostooling/setup-ros-docker:ubuntu-noble-ros-rolling-ros-base-latest
28-
steps:
29-
- uses: actions/checkout@v4
30-
31-
- name: Install typeshed
18+
- name: Install typeshed for mypy
19+
if: matrix.linter == 'mypy'
3220
run: sudo apt update && sudo apt install -y python3-typeshed
3321

3422
- uses: ros-tooling/action-ros-lint@v0.1
3523
with:
36-
linter: mypy
24+
linter: ${{ matrix.linter }}
3725
distribution: rolling
38-
package-name: >-
39-
nav2_smac_planner
40-
nav2_common
41-
nav2_bringup
42-
nav2_collision_monitor
43-
nav2_costmap_2d
44-
opennav_docking
45-
nav2_lifecycle_manager
46-
nav2_loopback_sim
47-
nav2_map_server
48-
nav2_simple_commander
49-
nav2_system_tests
50-
arguments: --config tools/pyproject.toml
26+
package-name: "*"
27+
arguments: ${{ matrix.linter == 'mypy' && '--config tools/pyproject.toml' || '' }}
5128

5229
pre-commit:
5330
name: pre-commit
@@ -64,3 +41,4 @@ jobs:
6441
ament_xmllint,
6542
ament_flake8,
6643
ament_pep257,
44+
ament_mypy

.pre-commit-config.yaml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,3 +95,10 @@ repos:
9595
language: system
9696
types: [python]
9797
entry: ament_pep257
98+
- id: ament_mypy
99+
name: ament_mypy
100+
description: Check Python code style using mypy.
101+
language: system
102+
types: [python]
103+
args: ["--config", "tools/pyproject.toml"]
104+
entry: ament_mypy

tools/bt2img.py

Lines changed: 41 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
# for instructions
1818

1919
import argparse
20-
import xml.etree.ElementTree
20+
import xml.etree.ElementTree as ET
2121

2222
import graphviz # pip3 install graphviz
2323

@@ -75,16 +75,13 @@
7575
'SubTree',
7676
]
7777

78-
global xml_tree
7978

80-
81-
def main():
82-
global xml_tree
79+
def main() -> None:
8380
args = parse_command_line()
84-
xml_tree = xml.etree.ElementTree.parse(args.behavior_tree)
81+
xml_tree = ET.parse(args.behavior_tree)
8582
root_tree_name = find_root_tree_name(xml_tree)
8683
behavior_tree = find_behavior_tree(xml_tree, root_tree_name)
87-
dot = convert2dot(behavior_tree)
84+
dot = convert2dot(behavior_tree, xml_tree)
8885
if args.legend:
8986
legend = make_legend()
9087
legend.format = 'png'
@@ -96,7 +93,7 @@ def main():
9693
dot.render(args.image_out, view=args.display)
9794

9895

99-
def parse_command_line():
96+
def parse_command_line() -> argparse.Namespace:
10097
parser = argparse.ArgumentParser(
10198
description='Convert a behavior tree XML file to an image'
10299
)
@@ -124,11 +121,15 @@ def parse_command_line():
124121
return parser.parse_args()
125122

126123

127-
def find_root_tree_name(xml_tree):
128-
return xml_tree.getroot().get('main_tree_to_execute')
124+
def find_root_tree_name(xml_tree: ET.ElementTree) -> str:
125+
root = xml_tree.getroot()
126+
main_tree = root.get('main_tree_to_execute')
127+
if main_tree is None:
128+
raise RuntimeError('No main_tree_to_execute attribute found in XML root')
129+
return main_tree
129130

130131

131-
def find_behavior_tree(xml_tree, tree_name):
132+
def find_behavior_tree(xml_tree: ET.ElementTree, tree_name: str) -> ET.Element:
132133
trees = xml_tree.findall('BehaviorTree')
133134
if len(trees) == 0:
134135
raise RuntimeError('No behavior trees were found in the XML file')
@@ -141,33 +142,50 @@ def find_behavior_tree(xml_tree, tree_name):
141142

142143

143144
# Generate a dot description of the root of the behavior tree.
144-
def convert2dot(behavior_tree):
145+
def convert2dot(behavior_tree: ET.Element, xml_tree: ET.ElementTree) -> graphviz.Digraph:
145146
dot = graphviz.Digraph()
146147
root = behavior_tree
147148
parent_dot_name = str(hash(root))
148149
dot.node(parent_dot_name, root.get('ID'), shape='box')
149-
convert_subtree(dot, root, parent_dot_name)
150+
convert_subtree(dot, root, parent_dot_name, xml_tree)
150151
return dot
151152

152153

153154
# Recursive function. We add the children to the dot file, and then recursively
154155
# call this function on the children. Nodes are given an ID that is the hash
155156
# of the node to ensure each is unique.
156-
def convert_subtree(dot, parent_node, parent_dot_name):
157+
def convert_subtree(
158+
dot: graphviz.Digraph,
159+
parent_node: ET.Element,
160+
parent_dot_name: str,
161+
xml_tree: ET.ElementTree,
162+
) -> None:
157163
if parent_node.tag == 'SubTree':
158-
add_sub_tree(dot, parent_dot_name, parent_node)
164+
add_sub_tree(dot, parent_dot_name, parent_node, xml_tree)
159165
else:
160-
add_nodes(dot, parent_dot_name, parent_node)
166+
add_nodes(dot, parent_dot_name, parent_node, xml_tree)
161167

162168

163-
def add_sub_tree(dot, parent_dot_name, parent_node):
169+
def add_sub_tree(
170+
dot: graphviz.Digraph,
171+
parent_dot_name: str,
172+
parent_node: ET.Element,
173+
xml_tree: ET.ElementTree,
174+
) -> None:
164175
root_tree_name = parent_node.get('ID')
176+
if root_tree_name is None:
177+
raise RuntimeError('SubTree node has no ID attribute')
165178
dot.node(parent_dot_name, root_tree_name, shape='box')
166179
behavior_tree = find_behavior_tree(xml_tree, root_tree_name)
167-
convert_subtree(dot, behavior_tree, parent_dot_name)
180+
convert_subtree(dot, behavior_tree, parent_dot_name, xml_tree)
168181

169182

170-
def add_nodes(dot, parent_dot_name, parent_node):
183+
def add_nodes(
184+
dot: graphviz.Digraph,
185+
parent_dot_name: str,
186+
parent_node: ET.Element,
187+
xml_tree: ET.ElementTree,
188+
) -> None:
171189
for node in list(parent_node):
172190
label = make_label(node)
173191
dot.node(
@@ -179,12 +197,12 @@ def add_nodes(dot, parent_dot_name, parent_node):
179197
)
180198
dot_name = str(hash(node))
181199
dot.edge(parent_dot_name, dot_name)
182-
convert_subtree(dot, node, dot_name)
200+
convert_subtree(dot, node, dot_name, xml_tree)
183201

184202

185203
# The node label contains the:
186204
# type, the name if provided, and the parameters.
187-
def make_label(node):
205+
def make_label(node: ET.Element) -> str:
188206
label = "< <table border='0' cellspacing='0' cellpadding='0'>"
189207
label += f"<tr><td align='text'><i>{node.tag}</i></td></tr>"
190208
name = node.get('name')
@@ -197,7 +215,7 @@ def make_label(node):
197215
return label
198216

199217

200-
def node_color(node_type):
218+
def node_color(node_type: str) -> str:
201219
if node_type in control_nodes:
202220
return 'chartreuse4'
203221
if node_type in action_nodes:
@@ -213,7 +231,7 @@ def node_color(node_type):
213231

214232

215233
# creates a legend which can be provided with the other images.
216-
def make_legend():
234+
def make_legend() -> graphviz.Digraph:
217235
legend = graphviz.Digraph(graph_attr={'rankdir': 'LR'})
218236
legend.attr(label='Legend')
219237
legend.node('Unknown', shape='box', style='filled', color='grey')

tools/planner_benchmarking/metrics.py

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -23,11 +23,15 @@
2323
from geometry_msgs.msg import PoseStamped
2424
from nav2_simple_commander.robot_navigator import BasicNavigator
2525
import numpy as np
26+
from numpy.typing import NDArray
2627
import rclpy
28+
from rclpy.time import Time
2729
from transforms3d.euler import euler2quat
2830

2931

30-
def getPlannerResults(navigator, initial_pose, goal_pose, planners):
32+
def getPlannerResults(
33+
navigator: BasicNavigator, initial_pose: PoseStamped,
34+
goal_pose: PoseStamped, planners: list[str]) -> list[PoseStamped]:
3135
results = []
3236
for planner in planners:
3337
path = navigator._getPathImpl(initial_pose, goal_pose, planner, use_start=True)
@@ -39,7 +43,9 @@ def getPlannerResults(navigator, initial_pose, goal_pose, planners):
3943
return results
4044

4145

42-
def getRandomStart(costmap, max_cost, side_buffer, time_stamp, res):
46+
def getRandomStart(
47+
costmap: NDArray[np.float32], max_cost: int,
48+
side_buffer: int, time_stamp: Time, res: float) -> PoseStamped:
4349
start = PoseStamped()
4450
start.header.frame_id = 'map'
4551
start.header.stamp = time_stamp
@@ -61,7 +67,9 @@ def getRandomStart(costmap, max_cost, side_buffer, time_stamp, res):
6167
return start
6268

6369

64-
def getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res):
70+
def getRandomGoal(
71+
costmap: NDArray[np.float32], start: PoseStamped,
72+
max_cost: int, side_buffer: int, time_stamp: Time, res: float) -> PoseStamped:
6573
goal = PoseStamped()
6674
goal.header.frame_id = 'map'
6775
goal.header.stamp = time_stamp
@@ -91,7 +99,7 @@ def getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res):
9199
return goal
92100

93101

94-
def main():
102+
def main() -> None:
95103
rclpy.init()
96104

97105
navigator = BasicNavigator()
@@ -110,7 +118,7 @@ def main():
110118
max_cost = 210
111119
side_buffer = 100
112120
time_stamp = navigator.get_clock().now().to_msg()
113-
results = []
121+
results: list[PoseStamped] = []
114122
seed(33)
115123

116124
random_pairs = 100

tools/planner_benchmarking/planning_benchmark_bringup.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
from launch_ros.actions import Node
2222

2323

24-
def generate_launch_description():
24+
def generate_launch_description() -> LaunchDescription:
2525
nav2_bringup_dir = get_package_share_directory('nav2_bringup')
2626
config = os.path.join(
2727
get_package_share_directory('nav2_bringup'), 'params', 'nav2_params.yaml'

tools/planner_benchmarking/process_data.py

Lines changed: 20 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -18,28 +18,31 @@
1818
import pickle
1919

2020
import matplotlib.pylab as plt
21+
from nav2_msgs.action import ComputePathToPose
22+
from nav2_msgs.msg import Costmap
23+
from nav_msgs.msg import Path
2124
import numpy as np
2225
import seaborn as sns
2326
from tabulate import tabulate
2427

2528

26-
def getPaths(results):
29+
def getPaths(results: list[ComputePathToPose.Result]) -> list[Path]:
2730
paths = []
2831
for result in results:
2932
for path in result:
3033
paths.append(path.path)
3134
return paths
3235

3336

34-
def getTimes(results):
37+
def getTimes(results: list[ComputePathToPose.Result]) -> list[float]:
3538
times = []
3639
for result in results:
3740
for time in result:
3841
times.append(time.planning_time.nanosec / 1e09 + time.planning_time.sec)
3942
return times
4043

4144

42-
def getMapCoordsFromPaths(paths, resolution):
45+
def getMapCoordsFromPaths(paths: list[Path], resolution: float) -> list[list[float]]:
4346
coords = []
4447
for path in paths:
4548
x = []
@@ -52,8 +55,8 @@ def getMapCoordsFromPaths(paths, resolution):
5255
return coords
5356

5457

55-
def getPathLength(path):
56-
path_length = 0
58+
def getPathLength(path: Path) -> float:
59+
path_length = 0.0
5760
x_prev = path.poses[0].pose.position.x
5861
y_prev = path.poses[0].pose.position.y
5962
for i in range(1, len(path.poses)):
@@ -67,7 +70,7 @@ def getPathLength(path):
6770
return path_length
6871

6972

70-
def plotResults(costmap, paths):
73+
def plotResults(costmap: Costmap, paths: list[Path]) -> None:
7174
coords = getMapCoordsFromPaths(paths, costmap.metadata.resolution)
7275
data = np.asarray(costmap.data)
7376
data.resize(costmap.metadata.size_y, costmap.metadata.size_x)
@@ -82,12 +85,14 @@ def plotResults(costmap, paths):
8285
plt.show()
8386

8487

85-
def averagePathCost(paths, costmap, num_of_planners):
88+
def averagePathCost(
89+
paths: list[Path], costmap: Costmap,
90+
num_of_planners: int) -> list[list[float]]:
8691
coords = getMapCoordsFromPaths(paths, costmap.metadata.resolution)
8792
data = np.asarray(costmap.data)
8893
data.resize(costmap.metadata.size_y, costmap.metadata.size_x)
8994

90-
average_path_costs = []
95+
average_path_costs: list[list[float]] = []
9196
for i in range(num_of_planners):
9297
average_path_costs.append([])
9398

@@ -102,12 +107,12 @@ def averagePathCost(paths, costmap, num_of_planners):
102107
return average_path_costs
103108

104109

105-
def maxPathCost(paths, costmap, num_of_planners):
110+
def maxPathCost(paths: list[Path], costmap: Costmap, num_of_planners: int) -> list[list[float]]:
106111
coords = getMapCoordsFromPaths(paths, costmap.metadata.resolution)
107112
data = np.asarray(costmap.data)
108113
data.resize(costmap.metadata.size_y, costmap.metadata.size_x)
109114

110-
max_path_costs = []
115+
max_path_costs: list[list[float]] = []
111116
for i in range(num_of_planners):
112117
max_path_costs.append([])
113118

@@ -124,7 +129,7 @@ def maxPathCost(paths, costmap, num_of_planners):
124129
return max_path_costs
125130

126131

127-
def main():
132+
def main() -> None:
128133

129134
print('Read data')
130135
with open(os.getcwd() + '/results.pickle', 'rb') as f:
@@ -137,18 +142,17 @@ def main():
137142
costmap = pickle.load(f)
138143

139144
paths = getPaths(results)
140-
path_lengths = []
145+
path_lengths_list = []
141146

142147
for path in paths:
143-
path_lengths.append(getPathLength(path))
144-
path_lengths = np.asarray(path_lengths)
148+
path_lengths_list.append(getPathLength(path))
149+
path_lengths = np.asarray(path_lengths_list)
145150
total_paths = len(paths)
146151

147152
path_lengths.resize((int(total_paths / len(planners)), len(planners)))
148153
path_lengths = path_lengths.transpose()
149154

150-
times = getTimes(results)
151-
times = np.asarray(times)
155+
times = np.asarray(getTimes(results))
152156
times.resize((int(total_paths / len(planners)), len(planners)))
153157
times = np.transpose(times)
154158

0 commit comments

Comments
 (0)