Skip to content

Commit

Permalink
Merge pull request #32 from robotique-ecam/ci/enforce-codingstyle-checks
Browse files Browse the repository at this point in the history
Use black python code formatter
  • Loading branch information
3wnbr1 authored Feb 25, 2021
2 parents a4cc383 + 289b7ea commit f62e12e
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 8 deletions.
17 changes: 17 additions & 0 deletions .github/workflows/autoblack.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
name: Python Linter
on: [push]
jobs:
build:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v1
- name: Set up Python
uses: actions/setup-python@v1
with:
python-version: 3.9

- name: Install Black
run: pip install black

- name: Run black --check .
run: black --check .
27 changes: 19 additions & 8 deletions src/modules/localisation/localisation/localisation_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
from visualization_msgs.msg import MarkerArray
from tf2_ros import StaticTransformBroadcaster


class Localisation(rclpy.node.Node):
"""Robot localisation node."""

Expand All @@ -24,16 +25,22 @@ def __init__(self):
self._x, self._y, self._theta = self.fetchStartPosition()
self._tf_brodcaster = StaticTransformBroadcaster(self)
self._tf = TransformStamped()
self._tf.header.frame_id = 'map'
self._tf.child_frame_id = 'odom'
self._tf.header.frame_id = "map"
self._tf.child_frame_id = "odom"
self.update_transform()
self.subscription_ = self.create_subscription(
MarkerArray, '/allies_positions_markers', self.allies_subscription_callback, 10)
MarkerArray,
"/allies_positions_markers",
self.allies_subscription_callback,
10,
)
self.subscription_ # prevent unused variable warning
self.tf_publisher_ = self.create_publisher(TransformStamped, 'adjust_odometry', 10)
self.tf_publisher_ = self.create_publisher(
TransformStamped, "adjust_odometry", 10
)
self.last_odom_update = 0
self.get_logger().info(f'Default side is {self.side.value}')
self.get_logger().info('Localisation node is ready')
self.get_logger().info(f"Default side is {self.side.value}")
self.get_logger().info("Localisation node is ready")

def _on_set_parameters(self, params):
"""Handle Parameter events especially for side."""
Expand Down Expand Up @@ -111,9 +118,12 @@ def update_transform(self):

def allies_subscription_callback(self, msg):
"""Identity the robot marker in assurancetourix marker_array detection
publish the transformation for drive to readjust odometry"""
publish the transformation for drive to readjust odometry"""
for allie_marker in msg.markers:
if allie_marker.text.lower() == self.robot and (self.get_clock().now().to_msg().sec - self.last_odom_update) > 5:
if (
allie_marker.text.lower() == self.robot
and (self.get_clock().now().to_msg().sec - self.last_odom_update) > 5
):
self._x = allie_marker.pose.position.x
self._y = allie_marker.pose.position.y
q = allie_marker.pose.orientation
Expand All @@ -126,6 +136,7 @@ def allies_subscription_callback(self, msg):
self.tf_publisher_.publish(self._tf)
self.last_odom_update = self.get_clock().now().to_msg().sec


def main(args=None):
"""Entrypoint."""
rclpy.init(args=args)
Expand Down

0 comments on commit f62e12e

Please sign in to comment.