Skip to content

Commit

Permalink
Merge pull request #1 from rafal-gorecki/test-black
Browse files Browse the repository at this point in the history
Test black
  • Loading branch information
rafal-gorecki authored Sep 19, 2023
2 parents 577e319 + 39769c8 commit 4ca2c1f
Show file tree
Hide file tree
Showing 12 changed files with 225 additions and 116 deletions.
13 changes: 13 additions & 0 deletions .github/workflows/black.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
name: Black python lint

on:
workflow_call:
pull_request:
push:

jobs:
lint:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- uses: psf/black@stable
12 changes: 5 additions & 7 deletions rosbot_bringup/launch/bringup.launch.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
from launch import LaunchDescription
from launch_ros.actions import Node, SetParameter
from launch.substitutions import PathJoinSubstitution
from launch.substitutions import PathJoinSubstitution
from ament_index_python.packages import get_package_share_directory
from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import (
LaunchConfiguration,
PathJoinSubstitution
)
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution


def generate_launch_description():
use_sim = LaunchConfiguration("use_sim")
Expand All @@ -29,7 +27,7 @@ def generate_launch_description():
"simulation_engine",
default_value="webots",
description="Which simulation engine to be used",
choices=["ignition-gazebo", "gazebo-classic", "webots"]
choices=["ignition-gazebo", "gazebo-classic", "webots"],
)

rosbot_controller = get_package_share_directory("rosbot_controller")
Expand Down Expand Up @@ -77,7 +75,7 @@ def generate_launch_description():
declare_simulation_engine_arg,
SetParameter(name="use_sim_time", value=use_sim),
controller_launch,
robot_localization_node
robot_localization_node,
]

return LaunchDescription(actions)
9 changes: 6 additions & 3 deletions rosbot_controller/launch/controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,10 @@ def generate_launch_description():
declare_mecanum_arg = DeclareLaunchArgument(
"mecanum",
default_value="False",
description="Whether to use mecanum drive controller (otherwise diff drive controller is used)",
description=(
"Whether to use mecanum drive controller "
"(otherwise diff drive controller is used)"
),
)

use_sim = LaunchConfiguration("use_sim")
Expand All @@ -58,7 +61,7 @@ def generate_launch_description():
"simulation_engine",
default_value="webots",
description="Which simulation engine to be used",
choices=["ignition-gazebo", "gazebo-classic", "webots"]
choices=["ignition-gazebo", "gazebo-classic", "webots"],
)

controller_config_name = PythonExpression(
Expand Down Expand Up @@ -196,4 +199,4 @@ def generate_launch_description():
delay_imu_broadcaster_spawner_after_robot_controller_spawner,
]

return LaunchDescription(actions)
return LaunchDescription(actions)
30 changes: 14 additions & 16 deletions rosbot_controller/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,28 +2,26 @@
from glob import glob
from setuptools import find_packages, setup

package_name = 'rosbot_controller'
package_name = "rosbot_controller"

setup(
name=package_name,
version='0.8.0',
packages=find_packages(exclude=['test']),
version="0.8.0",
packages=find_packages(exclude=["test"]),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py')),
(os.path.join('share', package_name, 'config'), glob('config/*.yaml')),
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
("share/" + package_name, ["package.xml"]),
(os.path.join("share", package_name, "launch"), glob("launch/*.launch.py")),
(os.path.join("share", package_name, "config"), glob("config/*.yaml")),
],
install_requires=['setuptools'],
install_requires=["setuptools"],
zip_safe=True,
maintainer='Husarion',
maintainer_email='[email protected]',
description='Hardware configuration for ROSbot 2, 2R, PRO',
license='Apache License 2.0',
tests_require=['pytest'],
maintainer="Husarion",
maintainer_email="[email protected]",
description="Hardware configuration for ROSbot 2, 2R, PRO",
license="Apache License 2.0",
tests_require=["pytest"],
entry_points={
'console_scripts': [
],
"console_scripts": [],
},
)
37 changes: 18 additions & 19 deletions rosbot_controller/test/controllers_test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,44 +28,37 @@ class ControllersTestNode(Node):

__test__ = False

def __init__(self, name='test_node'):
def __init__(self, name="test_node"):
super().__init__(name)
self.joint_state_msg_event = Event()
self.odom_msg_event = Event()
self.imu_msg_event = Event()

def create_test_subscribers_and_publishers(self):
self.joint_state_sub = self.create_subscription(
JointState,
'/joint_states',
self.joint_states_callback,
10
JointState, "/joint_states", self.joint_states_callback, 10
)

self.odom_sub = self.create_subscription(
Odometry,
'/rosbot_base_controller/odom',
self.odometry_callback,
10
Odometry, "/rosbot_base_controller/odom", self.odometry_callback, 10
)

self.imu_sub = self.create_subscription(
Imu,
'/imu_broadcaster/imu',
self.joint_states_callback,
10
Imu, "/imu_broadcaster/imu", self.joint_states_callback, 10
)

self.imu_publisher = self.create_publisher(Imu, '_imu/data_raw', 10)
self.imu_publisher = self.create_publisher(Imu, "_imu/data_raw", 10)

self.joint_states_publisher = self.create_publisher(
JointState, '_motors_response', 10)
JointState, "_motors_response", 10
)

self.timer = None

def start_node_thread(self):
self.ros_spin_thread = Thread(
target=lambda node: rclpy.spin(node), args=(self,))
target=lambda node: rclpy.spin(node), args=(self,)
)
self.ros_spin_thread.start()

def joint_states_callback(self, data):
Expand All @@ -79,17 +72,23 @@ def imu_callback(self, data):

def start_publishing_fake_hardware(self):
self.timer = self.create_timer(
1.0/self.ROSBOT_HARDWARE_PUBLISHERS_RATE, self.publish_fake_hardware_messages)
1.0 / self.ROSBOT_HARDWARE_PUBLISHERS_RATE,
self.publish_fake_hardware_messages,
)

def publish_fake_hardware_messages(self):
imu_msg = Imu()
imu_msg.header.stamp = self.get_clock().now().to_msg()
imu_msg.header.frame_id = 'imu_link'
imu_msg.header.frame_id = "imu_link"

joint_state_msg = JointState()
joint_state_msg.header.stamp = self.get_clock().now().to_msg()
joint_state_msg.name = [
'fl_wheel_joint', 'fr_wheel_joint', 'rl_wheel_joint', 'rr_wheel_joint']
"fl_wheel_joint",
"fr_wheel_joint",
"rl_wheel_joint",
"rr_wheel_joint",
]
joint_state_msg.position = [0.0, 0.0, 0.0, 0.0]
joint_state_msg.velocity = [0.0, 0.0, 0.0, 0.0]

Expand Down
23 changes: 23 additions & 0 deletions rosbot_controller/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_copyright.main import main
import pytest


@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=[".", "test"])
assert rc == 0, "Found errors"
37 changes: 19 additions & 18 deletions rosbot_controller/test/test_diff_drive_controllers.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,14 +23,9 @@
from launch.actions import IncludeLaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution

# Import submodule from this directory
import sys
import os
sys.path.append(os.path.abspath(os.path.dirname(__file__)+"./"))
from controllers_test_node import ControllersTestNode


@launch_pytest.fixture
def generate_test_description():
rosbot_controller = get_package_share_directory("rosbot_controller")
Expand All @@ -47,29 +42,31 @@ def generate_test_description():
launch_arguments={
"use_sim": "False",
"mecanum": "False",
"use_gpu": "False"
"use_gpu": "False",
}.items(),
)

return LaunchDescription([
bringup_launch
])
return LaunchDescription([bringup_launch])


@pytest.mark.launch(fixture=generate_test_description)
def test_controllers_startup_fail():
rclpy.init()
try:
node = ControllersTestNode('test_controllers_bringup')
node = ControllersTestNode("test_controllers_bringup")
node.create_test_subscribers_and_publishers()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, 'Received JointStates message, check joint_state_broadcaster!'
assert (
not msgs_received_flag
), "Received JointStates message, check joint_state_broadcaster!"
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, 'Received Odom message, check rosbot_base_controller!'
assert (
not msgs_received_flag
), "Received Odom message, check rosbot_base_controller!"
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert not msgs_received_flag, 'Received Imu message, check imu_broadcaster!'
assert not msgs_received_flag, "Received Imu message, check imu_broadcaster!"
finally:
rclpy.shutdown()

Expand All @@ -78,16 +75,20 @@ def test_controllers_startup_fail():
def test_controllers_startup_success():
rclpy.init()
try:
node = ControllersTestNode('test_controllers_bringup')
node = ControllersTestNode("test_controllers_bringup")
node.create_test_subscribers_and_publishers()
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert msgs_received_flag, 'Did not receive JointStates message, check joint_state_broadcaster!'
assert (
msgs_received_flag
), "Did not receive JointStates message, check joint_state_broadcaster!"
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
assert msgs_received_flag, 'Did not receive Odom message, check rosbot_base_controller!'
assert (
msgs_received_flag
), "Did not receive Odom message, check rosbot_base_controller!"
msgs_received_flag = node.joint_state_msg_event.wait(timeout=10.0)
assert msgs_received_flag, 'Did not receive Imu message, check imu_broadcaster!'
assert msgs_received_flag, "Did not receive Imu message, check imu_broadcaster!"
finally:
rclpy.shutdown()
25 changes: 25 additions & 0 deletions rosbot_controller/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from ament_flake8.main import main_with_errors
import pytest


@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, "Found %d code style errors / warnings:\n" % len(
errors
) + "\n".join(errors)
Loading

0 comments on commit 4ca2c1f

Please sign in to comment.