Skip to content

Commit

Permalink
Fixed the linter errors (#263)
Browse files Browse the repository at this point in the history
* Fixed the linter errors

* Fixed linter errors
  • Loading branch information
BenStarmerSmith authored Jun 1, 2022
1 parent ae1332c commit 0befec1
Show file tree
Hide file tree
Showing 8 changed files with 51 additions and 60 deletions.
2 changes: 1 addition & 1 deletion .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ jobs:
docker:
- image: public.ecr.aws/shadowrobot/build-tools:focal-noetic
environment:
toolset_branch: master
toolset_branch: lint
server_type: circle
ros_release_name: noetic
ubuntu_version_name: focal
Expand Down
2 changes: 1 addition & 1 deletion aws.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ settings:
tag: focal-noetic
template_project_name: template_unit_tests_and_code_coverage
toolset:
branch: master
branch: lint
modules:
- check_cache
- code_coverage
Expand Down
6 changes: 2 additions & 4 deletions sr_edc_muscle_tools/bin/example_move_joint.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3
#
# Copyright 2019 Shadow Robot Company Ltd.
# Copyright 2019, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -14,11 +14,9 @@
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import
import roslib
import math
import rospy
from std_msgs.msg import Float64
import math

rospy.init_node('example1')

Expand Down
19 changes: 8 additions & 11 deletions sr_edc_muscle_tools/bin/example_reading_sensors.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3
#
# Copyright 2019 Shadow Robot Company Ltd.
# Copyright 2019, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -14,19 +14,15 @@
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import
import roslib
import rospy
from std_msgs.msg import Float64
from sr_robot_msgs.msg import JointMusclePositionControllerState
import math

# A callback function for the state messages we are reading.
status = None


def state_cb(data):
global status
global status # pylint: disable=W0603
status = data


Expand All @@ -38,10 +34,11 @@ def state_cb(data):
JointMusclePositionControllerState, state_cb)

print("Try moving ffj3")
r = rospy.Rate(1) # hz
rate_speed = rospy.Rate(1) # hz
while not rospy.is_shutdown():
if status:
print("ffj3 position:%s radians pressure0:%s pressure1:%s" % (status.process_value,
status.muscle_pressure_0,
status.muscle_pressure_1))
r.sleep()
status_string = (f"ffj3 position:{status.process_value} radians"
f" pressure0:{status.muscle_pressure_0}"
f" pressure1:{status.muscle_pressure_1}")
print(status_string)
rate_speed.sleep()
24 changes: 10 additions & 14 deletions sr_edc_muscle_tools/bin/example_sendupdate.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3
#
# Copyright 2019 Shadow Robot Company Ltd.
# Copyright 2019, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -14,17 +14,13 @@
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import
import roslib
import math
import rospy
from sr_robot_msgs.msg import sendupdate, joint
from sr_robot_msgs.msg import sendupdate
from std_msgs.msg import Float64
import math

#
# Small demo of moving a number of joints together.
# Flexes the 2 fingers and then waves the wrist.
#


# We set up all the publishers needed for all joints in a dict and create a simple
Expand All @@ -40,16 +36,16 @@
joint_pubs[jname] = rospy.Publisher(topic, Float64, latch=True)


def sendupdate(joints):
def sendupdate(joints): # pylint: disable=E0102
print("Sending:")
for jname in joints:
if jname not in joint_pubs:
print("\tJoint %s not found" % jname)
for jointname in joints:
if jointname not in joint_pubs:
print(f"\tJoint {jointname} not found")
return
msg = Float64()
msg.data = math.radians(float(joints[jname]))
print("\t" + jname + ": " + str(joints[jname]))
joint_pubs[jname].publish(msg)
msg.data = math.radians(float(joints[jointname]))
print(f"\t{jointname}: {str(joints[jointname])}")
joint_pubs[jointname].publish(msg)


rospy.init_node('example_sendupdate')
Expand Down
6 changes: 2 additions & 4 deletions sr_robot_lib/examples/compute_joint_0_target.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3
#
# Copyright 2019 Shadow Robot Company Ltd.
# Copyright 2019, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -14,15 +14,13 @@
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import
import roslib
import rospy

from sensor_msgs.msg import JointState
from std_msgs.msg import Float64


class Merger(object):
class Merger:

def __init__(self):
self.subscriber = rospy.Subscriber(
Expand Down
43 changes: 23 additions & 20 deletions sr_robot_lib/python_lib/sr_robot_lib/etherCAT_hand_lib.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#!/usr/bin/env python3
# pylint: disable=C0103 # Needed for name of class and file.
#
# Copyright 2011 Shadow Robot Company Ltd.
# Copyright 2011, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -15,12 +16,10 @@
# with this program. If not, see <http://www.gnu.org/licenses/>.
#

from __future__ import absolute_import
import rospy

import time
import math
import re
import rospy

from std_msgs.msg import Float64
from sensor_msgs.msg import JointState
Expand All @@ -29,7 +28,7 @@
from sr_utilities.hand_finder import HandFinder


class EtherCAT_Hand_Lib(object):
class EtherCAT_Hand_Lib:

"""
Useful python library to communicate with the etherCAT hand.
Expand All @@ -51,7 +50,7 @@ def __init__(self):
self.hand_finder = HandFinder()
self.hand_params = self.hand_finder.get_hand_parameters()
self.hand_id = ''
if len(self.hand_params.mapping) is not 0:
if len(self.hand_params.mapping) != 0:
self.hand_id = next(iter(self.hand_params.mapping.values()))
self.debug_subscriber = None
self.joint_state_subscriber = None
Expand Down Expand Up @@ -84,7 +83,7 @@ def __init__(self):
pass

for mapping in joint_to_sensor_mapping:
if mapping[0] is 1:
if mapping[0] == 1:
if "THJ5" in mapping[1][0]:
self.compounds["THJ5"] = [["THJ5A", mapping[1][1]],
["THJ5B", mapping[2][1]]]
Expand Down Expand Up @@ -148,11 +147,11 @@ def get_effort(self, joint_name):
raise
return value

def start_record(self, joint_name, callback):
def start_record(self, callback):
self.record_js_callback = callback

def stop_record(self, joint_name):
self.callback = None
def stop_record(self):
self.record_js_callback = None

def set_pid(self, joint_name, pid_parameters):
"""
Expand All @@ -174,7 +173,7 @@ def set_pid(self, joint_name, pid_parameters):
pid_parameters["sign"])

def debug_callback(self, msg):
if not(all(v == 0 for v in msg.sensors)):
if not all(v == 0 for v in msg.sensors):
self.raw_values = msg.sensors

def joint_state_callback(self, msg):
Expand Down Expand Up @@ -209,29 +208,33 @@ def get_raw_value(self, sensor_name):

def get_raw_value_index(self, sensor_name):
try:
return_value = None
if sensor_name in list(self.compounds.keys()):
indices = []
for sub_compound in self.compounds[sensor_name]:
indices.append(self.sensors.index(sub_compound[0]))
return indices
return_value = indices
else:
return self.sensors.index(sensor_name)
except Exception as e:
rospy.logerr("Error while getting the raw value index of sensor '{}': \n{}".format(sensor_name, e))
return_value = self.sensors.index(sensor_name)
return return_value
except Exception as exception:
rospy.logerr(f"Error while getting the raw value index of sensor '{sensor_name}': \n{exception}")
return None

def get_compound_names(self, sensor_name):
try:
return_value = None
if sensor_name in list(self.compounds.keys()):
names = []
for sub_compound in self.compounds[sensor_name]:
names.append(sub_compound[0])
return names
return_value = names
else:
rospy.logwarn("{} is not a multi-sensor joint, returning joint name.".format(sensor_name))
return sensor_name
except Exception as e:
rospy.logerr("Error while getting the sensor names of compound sensor '{}': \n{}".format(sensor_name, e))
rospy.logwarn(f"{sensor_name} is not a multi-sensor joint, returning joint name.")
return_value = sensor_name
return return_value
except Exception as exception:
rospy.logerr(f"Error while getting the sensor names of compound sensor '{sensor_name}': \n{exception}")
return None

def get_average_raw_value(self, sensor_name, number_of_samples=10, accept_zeros=True):
Expand Down
9 changes: 4 additions & 5 deletions sr_tactile_sensor_controller/scripts/biotac_republisher
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3

# Copyright 2015 Shadow Robot Company Ltd.
# Copyright 2015, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -14,13 +14,12 @@
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import
import rospy
from sr_robot_msgs.msg import BiotacAll, Biotac
from sr_utilities.hand_finder import HandFinder


class BiotacRepublisher(object):
class BiotacRepublisher:
"""
Listens to BiotacAll and republished 5 Biotac
"""
Expand All @@ -36,8 +35,8 @@ class BiotacRepublisher(object):
for hand in self._hand_mapping.values():
self._publishers[hand] = []
for i in range(self._nb_fingers):
self._publishers[hand].append(rospy.Publisher(hand + "/biotac_" + str(i), Biotac, queue_size=10))
self._subscribers[hand] = rospy.Subscriber(hand + "/tactile", BiotacAll, self._tactile_cb, hand)
self._publishers[hand].append(rospy.Publisher(f"{hand}/biotac_{str(i)}", Biotac, queue_size=10))
self._subscribers[hand] = rospy.Subscriber(f"{hand}/tactile", BiotacAll, self._tactile_cb, hand)

def _tactile_cb(self, msg, hand):
for i in range(self._nb_fingers):
Expand Down

0 comments on commit 0befec1

Please sign in to comment.