Skip to content

Commit 994be7c

Browse files
authored
Fix CI (#191)
* Fix CI * Trigger * Trigger * Underscore * Update
1 parent 912f68f commit 994be7c

File tree

4 files changed

+33
-34
lines changed

4 files changed

+33
-34
lines changed

.github/workflows/test.yml

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,21 @@
11
name: CI
22

3-
on:
3+
on:
44
pull_request:
5-
types: [opened, synchronize, reopened, ready_for_review]
5+
types: [opened, synchronize, reopened, labeled, unlabeled]
66

77
jobs:
88
industrial_ci:
99
strategy:
1010
matrix:
11-
env:
12-
- {ROS_DISTRO: foxy, ROS_REPO: testing}
13-
- {ROS_DISTRO: foxy, ROS_REPO: main}
14-
- {ROS_DISTRO: rolling, ROS_REPO: testing}
15-
- {ROS_DISTRO: rolling, ROS_REPO: main}
11+
ROS_REPO: [main, testing]
12+
ROS_DISTRO: [foxy, rolling]
1613
runs-on: ubuntu-latest
1714
steps:
1815
- uses: actions/checkout@v1
1916
with:
2017
submodules: recursive
2118
- uses: 'ros-industrial/industrial_ci@master'
22-
env: ${{matrix.env}}
19+
env:
20+
ROS_REPO: ${{matrix.ROS_REPO}}
21+
ROS_DISTRO: ${{matrix.ROS_DISTRO}}

webots_ros2_core/webots_ros2_core/trajectory_follower.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -245,17 +245,17 @@ def update(self, goal_handle):
245245
last_point_start = Duration.from_msg(trajectory.joint_trajectory.points[-1].time_from_start)
246246
if (now - trajectory.start_time) <= last_point_start:
247247
# Sending intermediate points
248-
trajectory.lastPointSent = False
248+
trajectory.last_point_sent = False
249249
setpoint = sample_trajectory(trajectory.joint_trajectory,
250250
now - trajectory.start_time)
251251
for name in trajectory.joint_trajectory.joint_names:
252252
index = trajectory.joint_trajectory.joint_names.index(name)
253253
set_position_in_limit(self.__motors[name], setpoint.positions[index])
254254
# Velocity control is not used on the real robot and gives
255255
# bad results in the simulation
256-
elif not trajectory.lastPointSent:
256+
elif not trajectory.last_point_sent:
257257
# All intermediate points sent, sending last point to make sure we reach the goal
258-
trajectory.lastPointSent = True
258+
trajectory.last_point_sent = True
259259
setpoint = sample_trajectory(trajectory.joint_trajectory, last_point_start)
260260
for name in trajectory.joint_trajectory.joint_names:
261261
index = trajectory.joint_trajectory.joint_names.index(name)
@@ -268,7 +268,7 @@ def update(self, goal_handle):
268268
tolerances = [0.1] * len(last_point.positions)
269269
for name in trajectory.joint_trajectory.joint_names:
270270
reference_positions.append(position[name])
271-
for tolerance in trajectory.goalTolerance:
271+
for tolerance in trajectory.goal_tolerance:
272272
if tolerance.name == name:
273273
tolerances[len(reference_positions) - 1] = tolerance.position
274274
break

webots_ros2_importer/webots_ros2_importer/urdf2proto.py

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
from ament_index_python.packages import get_package_share_directory
2323

2424
sys.path.append(os.path.join(os.path.dirname(os.path.realpath(__file__)), 'urdf2webots'))
25+
# deepcode ignore C0413: We need to import the library first
2526
from urdf2webots.importer import convert2urdf # noqa: E402
2627

2728

@@ -53,7 +54,7 @@ def main(args=None, input=None):
5354
'the first 3 joints of your robot to the specified values, '
5455
'and leave the rest with their default value.')
5556
# use 'parse_known_args' because ROS2 adds a lot of internal arguments
56-
arguments, unknown = parser.parse_known_args()
57+
arguments, _ = parser.parse_known_args()
5758
file = os.path.abspath(input) if input is not None else os.path.abspath(arguments.inFile)
5859
if not file:
5960
sys.exit('Input file not specified (should be specified with the "--input" argument).')
@@ -65,24 +66,24 @@ def main(args=None, input=None):
6566
with open(file, 'r') as f:
6667
content = f.read()
6768
# look for package-relative file path and replace them
68-
urdfFile = file
69-
generatedFile = False
69+
urdf_file = file
70+
generated_file = False
7071
packages = re.findall(r'filename="package:\/\/([^\/]*)', content)
7172
for package in set(packages): # do the replacement
72-
packagePath = ''
73+
package_path = ''
7374
try:
74-
packagePath = get_package_share_directory(package)
75+
package_path = get_package_share_directory(package)
7576
except LookupError:
7677
sys.exit('This urdf depends on the "%s" package, but this package could not be found' %
7778
package)
78-
content = content.replace('package://%s' % package, '%s' % packagePath)
79+
content = content.replace('package://%s' % package, '%s' % package_path)
7980
if packages: # some package-relative file paths have been found
8081
# generate a temporary file with the replacement content
81-
urdfFile = tempfile.mkstemp(suffix='.urdf')[1]
82-
generatedFile = True
83-
with open(urdfFile, 'w') as f:
82+
urdf_file = tempfile.mkstemp(suffix='.urdf')[1]
83+
generated_file = True
84+
with open(urdf_file, 'w') as f:
8485
f.write(content)
85-
convert2urdf(inFile=urdfFile,
86+
convert2urdf(inFile=urdf_file,
8687
outFile=arguments.outFile,
8788
normal=arguments.normal,
8889
boxCollision=arguments.boxCollision,
@@ -93,8 +94,8 @@ def main(args=None, input=None):
9394
initRotation=arguments.initRotation,
9495
initPos=arguments.initPos)
9596
# remove temporary file
96-
if generatedFile:
97-
os.remove(urdfFile)
97+
if generated_file:
98+
os.remove(urdf_file)
9899

99100

100101
if __name__ == '__main__':

webots_ros2_importer/webots_ros2_importer/xacro2proto.py

Lines changed: 9 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -17,16 +17,15 @@
1717
import copy
1818
import os
1919
import sys
20-
import xacro
21-
2220
from tempfile import mkstemp
21+
import xacro
2322
from webots_ros2_importer import urdf2proto
2423

2524

2625
def main(args=None):
2726
# remvove arguments specific to the urdf2proto converter
28-
savedArgv = copy.copy(sys.argv)
29-
argsToRemove = [
27+
saved_argv = copy.copy(sys.argv)
28+
args_to_remove = [
3029
'--normal',
3130
'--box-collision',
3231
'--disable-mesh-optimization',
@@ -36,25 +35,25 @@ def main(args=None):
3635
'--tool-slot',
3736
'--rotation'
3837
]
39-
for arg in savedArgv:
40-
for argToRemove in argsToRemove:
41-
if arg.startswith(argToRemove):
38+
for arg in saved_argv:
39+
for arg_to_remove in args_to_remove:
40+
if arg.startswith(arg_to_remove):
4241
sys.argv.remove(arg)
4342
break
44-
for arg in argsToRemove:
43+
for arg in args_to_remove:
4544
if arg in sys.argv:
4645
sys.argv.remove(arg)
4746
# redirect stdout to temporary urdf file
4847
orig_stdout = sys.stdout
49-
file, path = mkstemp(suffix='.urdf')
48+
_, path = mkstemp(suffix='.urdf')
5049
with open(path, 'w') as f:
5150
sys.stdout = f
5251
# run xacro to urdf conversio
5352
sys.argv.append('--inorder')
5453
xacro.main()
5554
# restore stdout and arguments and then run urdf to proto conversion
5655
sys.stdout = orig_stdout
57-
sys.argv = savedArgv
56+
sys.argv = saved_argv
5857
urdf2proto.main(input=path)
5958
os.remove(path)
6059

0 commit comments

Comments
 (0)