Skip to content

Commit

Permalink
Fixing linter errors for Noetic. (ros-drivers#174)
Browse files Browse the repository at this point in the history
  • Loading branch information
Joshua Whitley authored Jun 2, 2020
1 parent 8d6cdd6 commit dc9e867
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 22 deletions.
5 changes: 1 addition & 4 deletions ps3joy/scripts/ps3joy_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -181,10 +181,7 @@ def __init__(self, deamon, inactivity_timeout=float(1e3000)):
step_error = 3

def init_ros(self):
try:
rospy.init_node('ps3joy', anonymous=True, disable_signals=True)
except:
print("rosnode init failed")
rospy.init_node('ps3joy', anonymous=True, disable_signals=True)
rospy.Subscriber("joy/set_feedback", sensor_msgs.msg.JoyFeedbackArray, self.set_feedback)
self.diagnostics = Diagnostics()
self.led_values = [1, 0, 0, 0]
Expand Down
17 changes: 5 additions & 12 deletions wiimote/nodes/wiimote_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -116,16 +116,14 @@ def runWiimoteNode(self):

rospy.spin()

except:
rospy.loginfo("Error in startup")
rospy.loginfo(sys.exc_info()[0])
# except:
# rospy.loginfo("Error in startup")
# rospy.loginfo(sys.exc_info()[0])
finally:
try:
wiimoteDevice.setRumble(False)
wiimoteDevice.setLEDs([False, False, False, False])
wiimoteDevice.shutdown()
except:
pass

def shutdown(self):
try:
Expand All @@ -134,8 +132,6 @@ def shutdown(self):
WiiSender.stop
NunSender.stop
WiimoteListener.stop
except:
pass


class WiimoteDataSender(threading.Thread):
Expand Down Expand Up @@ -743,15 +739,15 @@ def feedbackCallback(msg):
self.ledCommands[fb.id] = True
else:
self.ledCommands[fb.id] = False
except:
except IndexError:
rospy.logwarn("LED ID out of bounds, ignoring!")
elif fb.type == JoyFeedback.TYPE_RUMBLE:
if fb.id == 0:
if fb.intensity >= 0.5:
self.rumbleCommand = True
else:
self.rumbleCommand = False
else:
else IndexError:
rospy.logwarn("RUMBLE ID out of bounds, ignoring!")

self.wiiMote.setLEDs(self.ledCommands)
Expand Down Expand Up @@ -812,9 +808,6 @@ def calibrateCallback(req):
except CallbackStackEmptyError, e:
rospy.logfatal(str(e))

except:
excType, excValue, excTraceback = sys.exc_info()[:3]
traceback.print_exception(excType, excValue, excTraceback)
finally:
if (wiimoteNode is not None):
wiimoteNode.shutdown()
Expand Down
10 changes: 4 additions & 6 deletions wiimote/src/wiimote/WIIMote.py
Original file line number Diff line number Diff line change
Expand Up @@ -185,8 +185,6 @@ def __init__(self, theSampleRate=0, wiiStateLock=None, gatherCalibrationStats=Fa
try:
(factoryZero, factoryOne) = self.getNunchukFactoryCalibrationSettings()
self.setNunchukAccelerometerCalibration(factoryZero, factoryOne)
except:
pass

time.sleep(0.2)
self._wiiCallbackStack.push(self._steadyStateCallback)
Expand All @@ -196,10 +194,10 @@ def __init__(self, theSampleRate=0, wiiStateLock=None, gatherCalibrationStats=Fa
def _steadyStateCallback(self, state, theTime):
now = getTimeStamp()
if now - self._startTime >= self.sampleRate:
# If this Wiimote driver is to synchronize write
# access to the wii state variable (which is read from
# outside), then acquire the lock that was provided
# by the instantiator of this instance:
# If this Wiimote driver is to synchronize write
# access to the wii state variable (which is read from
# outside), then acquire the lock that was provided
# by the instantiator of this instance:
if self.wiiStateLock is not None:
self.wiiStateLock.acquire()
try:
Expand Down

0 comments on commit dc9e867

Please sign in to comment.