Skip to content

Commit

Permalink
Caught disconnect error
Browse files Browse the repository at this point in the history
  • Loading branch information
roboTJ101 committed Dec 22, 2014
1 parent 1e63372 commit 40480db
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 7 deletions.
3 changes: 2 additions & 1 deletion LICENSE
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
The MIT License (MIT)

Copyright (c) 2014 Thomas (TJ) Watson
Copyright (c) 2014 Danny Zhu
2014 Thomas (TJ) Watson

Permission is hereby granted, free of charge, to any person obtaining a copy of
this software and associated documentation files (the "Software"), to deal in
Expand Down
18 changes: 12 additions & 6 deletions scripts/myo-rawNode.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,8 @@
import threading
import time
import math

import serial
from serial.tools.list_ports import comports

from common import *
import rospy
from std_msgs.msg import String, UInt8, Header, MultiArrayLayout, MultiArrayDimension, Float64MultiArray
Expand Down Expand Up @@ -368,8 +366,16 @@ def on_arm(self, arm, xdir):
h(arm, xdir)

if __name__ == '__main__':

m = MyoRaw(sys.argv[1] if len(sys.argv) >= 2 else None)
connected = 0;
print("Initializing...")
while(connected == 0):
try:
m = MyoRaw(sys.argv[1] if len(sys.argv) >= 2 else None)
connected = 1;
except (ValueError, KeyboardInterrupt) as e:
print("Myo Armband not found. Attempting to connect...")
rospy.sleep(0.5)
pass

imuPub = rospy.Publisher('myo_imu', Imu, queue_size=10)
emgPub = rospy.Publisher('myo_emg', EmgArray, queue_size=10)
Expand Down Expand Up @@ -418,8 +424,8 @@ def proc_pose(p):
m.add_imu_handler(proc_imu)
m.add_arm_handler(proc_arm)
m.add_pose_handler(proc_pose)
m.connect()


m.connect()

try:

Expand Down

0 comments on commit 40480db

Please sign in to comment.