Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create pylint.yml #5

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 26 additions & 0 deletions .github/workflows/pylint.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
name: Pylint

on: [push]

jobs:
build:
runs-on: ubuntu-latest
container:
image: docker://ros:noetic-ros-base
# strategy:
# matrix:
# python-version: ["3.8", "3.9", "3.10"]
steps:
- uses: actions/checkout@v3
# - name: Set up Python ${{ matrix.python-version }}
# uses: actions/setup-python@v3
# with:
# python-version: ${{ matrix.python-version }}
- name: Install dependencies
run: |
python -m pip install --upgrade pip
pip install pylint
- name: Analysing the code with pylint
run: |
source /opt/ros/noetic/setup.bash
pylint $(git ls-files '*.py')
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
.vscode/
42 changes: 42 additions & 0 deletions .pylintrc
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@

[MESSAGES CONTROL]

# Only show warnings with the listed confidence levels. Leave empty to show
# all. Valid levels: HIGH, INFERENCE, INFERENCE_FAILURE, UNDEFINED
confidence=

# Disable the message, report, category or checker with the given id(s). You
# can either give multiple identifiers separated by comma (,) or put this
# option multiple times (only on the command line, not in the configuration
# file where it should appear only once).You can also use "--disable=all" to
# disable everything first and then reenable specific checks. For example, if
# you want to run only the similarities checker, you can use "--disable=all
# --enable=similarities". If you want to run only the classes checker, but have
# no Warning level messages displayed, use"--disable=all --enable=classes
# --disable=W"
disable=duplicate-code, # pylint-file-header: Fails in unit tests
missing-docstring, # pylint-file-header: Add DOCSTRINGS only where helpful
relative-import, # pylint-file-header: ignore for unit tests
redefined-outer-name, # pylint-file-header: conflicts with pytest fixtures
too-few-public-methods, # pylint-file-header: know what you are doing
bad-option-value # pylint-file-header: conflict with super-with-arguments in py34

# Enable the message, report, category or checker with the given id(s). You can
# either give multiple identifier separated by comma (,) or put this option
# multiple time (only on the command line, not in the configuration file where
# it should appear only once). See also the "--disable" option for examples.
# enable=

[BASIC]
# Good variable names which should always be accepted, separated by a comma
good-names=i,
j,
k,
m,
n,
dt,
tf,
_

# Bad variable names which should always be refused, separated by a comma
# bad-names=
69 changes: 54 additions & 15 deletions haruna/scripts/base_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,16 @@ def __init__(self, lim_vel_linear, lim_vel_angular, lim_acc_linear, lim_acc_angu
self._last_vel_linear = 0.0
self._last_vel_angular = 0.0
self._velocity_updated_timestamp = rospy.Time()
self._left_wheel_motor_velocity_publisher = rospy.Publisher('/left_wheel_motor_velocity_controller/command', Float64, queue_size=1)
self._right_wheel_motor_velocity_publisher = rospy.Publisher('/right_wheel_motor_velocity_controller/command', Float64, queue_size=1)
self._left_wheel_motor_velocity_publisher = rospy.Publisher(
'/left_wheel_motor_velocity_controller/command',
Float64,
queue_size=1
)
self._right_wheel_motor_velocity_publisher = rospy.Publisher(
'/right_wheel_motor_velocity_controller/command',
Float64,
queue_size=1
)
self._lim_vel_linear = lim_vel_linear
self._lim_vel_angular = lim_vel_angular
self._lim_acc_linear = lim_acc_linear
Expand All @@ -56,17 +64,28 @@ def proc(self, dt: float):
vel_linear = self._vel_linear
vel_angular = self._vel_angular

if (rospy.Time.now() - self._velocity_updated_timestamp >= rospy.Duration.from_sec(TIMEOUT_CMD_VEL_SEC)):
if (
rospy.Time.now() - self._velocity_updated_timestamp
>= rospy.Duration.from_sec(TIMEOUT_CMD_VEL_SEC)
):
self._vel_linear = 0.0
self._vel_angular = 0.0
vel_linear = 0.0
vel_angular = 0.0

vel_linear = clamp(vel_linear, self._last_vel_linear - self._lim_acc_linear * dt, self._last_vel_linear + self._lim_acc_linear * dt)
vel_angular = clamp(vel_angular, self._last_vel_angular - self._lim_acc_angular * dt, self._last_vel_angular + self._lim_acc_angular * dt)

vel_left = vel_linear - vel_angular * TREAD_WIDTH / 2;
vel_right = vel_linear + vel_angular * TREAD_WIDTH / 2;
vel_linear = clamp(
vel_linear,
self._last_vel_linear - self._lim_acc_linear * dt,
self._last_vel_linear + self._lim_acc_linear * dt
)
vel_angular = clamp(
vel_angular,
self._last_vel_angular - self._lim_acc_angular * dt,
self._last_vel_angular + self._lim_acc_angular * dt
)

vel_left = vel_linear - vel_angular * TREAD_WIDTH / 2
vel_right = vel_linear + vel_angular * TREAD_WIDTH / 2
self._left_wheel_motor_velocity_publisher.publish(Float64(vel_left / WHEEL_RADIUS))
self._right_wheel_motor_velocity_publisher.publish(Float64(-vel_right / WHEEL_RADIUS))

Expand All @@ -89,7 +108,13 @@ def __init__(self):
self._pos_y = 0.0
self._orientation_yaw = 0.0

def update_state(self, dist_left: float, dist_right: float, vel_left: float, vel_right: float):
def update_state(
self,
dist_left: float,
dist_right: float,
vel_left: float,
vel_right: float
):
self._dist_left = dist_left
self._dist_right = dist_right
self._vel_left = vel_left
Expand All @@ -115,18 +140,26 @@ def _send_transform(self):
self._tf_broadcaster.sendTransform(tf)

def clamp(n, smallest, largest):
return max(smallest, min(n, largest))
return max(smallest, min(n, largest))

if __name__ == '__main__':
rospy.init_node('controller')

rate_hz = float(rospy.get_param(PARAM_NAME_RATE, DEFAULT_RATE))

lim_vel_linear = float(rospy.get_param(PARAM_NAME_VEL_LIMIT_LINEAR, DEFAULT_VEL_LIMIT_LINEAR))
lim_vel_angular = float(rospy.get_param(PARAM_NAME_VEL_LIMIT_ANGULAR, DEFAULT_VEL_LIMIT_ANGULAR))
lim_vel_linear = float(
rospy.get_param(PARAM_NAME_VEL_LIMIT_LINEAR, DEFAULT_VEL_LIMIT_LINEAR)
)
lim_vel_angular = float(
rospy.get_param(PARAM_NAME_VEL_LIMIT_ANGULAR, DEFAULT_VEL_LIMIT_ANGULAR)
)

lim_acc_linear = float(rospy.get_param(PARAM_NAME_ACC_LIMIT_LINEAR, DEFAULT_ACC_LIMIT_LINEAR))
lim_acc_angular = float(rospy.get_param(PARAM_NAME_ACC_LIMIT_ANGULAR, DEFAULT_ACC_LIMIT_ANGULAR))
lim_acc_linear = float(
rospy.get_param(PARAM_NAME_ACC_LIMIT_LINEAR, DEFAULT_ACC_LIMIT_LINEAR)
)
lim_acc_angular = float(
rospy.get_param(PARAM_NAME_ACC_LIMIT_ANGULAR, DEFAULT_ACC_LIMIT_ANGULAR)
)

base = BaseController(lim_vel_linear, lim_vel_angular, lim_acc_linear, lim_acc_angular)
odom = Odometry()
Expand All @@ -137,7 +170,13 @@ def clamp(n, smallest, largest):

joint_states_subscriber = rospy.Subscriber(
TOPIC_NAME_JOINT_STATES, JointState,
lambda joint_state: odom.update_state(joint_state.position[0], joint_state.position[1], joint_state.velocity[0], joint_state.velocity[1]))
lambda joint_state: odom.update_state(
joint_state.position[0],
joint_state.position[1],
joint_state.velocity[0],
joint_state.velocity[1]
)
)

rate = rospy.Rate(rate_hz)
while not rospy.is_shutdown():
Expand Down
6 changes: 3 additions & 3 deletions haruna/tools/dcf_converter.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@ class PropertyValueFilter:
def __init__(self, rule):
self._rule = rule

def filter(self, property, value):
if property in self._rule:
return self._rule[property]
def filter(self, _property, value):
if _property in self._rule:
return self._rule[_property]
else:
return value

Expand Down