-
Notifications
You must be signed in to change notification settings - Fork 6
/
full_drive_run.py
77 lines (70 loc) · 2.42 KB
/
full_drive_run.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
#!/usr/bin/env python
from autonomous import *
from roboclaw import RoboClaw
import rospy
import tf
from std_msgs.msg import Float64MultiArray
from sensor_msgs.msg import Joy
import numpy as np
import signal
import sys
from serial.serialutil import SerialException as SerialException
import pdb
import os
#----------------------------------------------------
#SIGINT Handler to escape loops. Use Ctrl-C to exit
def sigint_handler(signal, frame):
sys.exit(0)
#----------------------------------------------------
#Used for running the rover using joystick
#----------------------------------------------------
#main program
if __name__ == "__main__":
signal.signal(signal.SIGINT, sigint_handler)
rospy.init_node("Drive_Node")
rospy.loginfo("Starting drive node")
r_time = rospy.Rate(1)
#------------------------------------------------
#Trying to connect to roboclaw drivers 1 and 2
# os.cmd('claw')
while(True):
try:
rightClaw = RoboClaw(0x80, "/dev/roboclawR", 9600)
break;
except SerialException:
rospy.logwarn("Couldn't connect to Right Claw at ttyACM0. trying again .\n Try running 'tty_permission' command ")
r_time.sleep()
rospy.loginfo("Connected to Right Claw")
while(True):
try:
leftClaw = RoboClaw(0x80, "/dev/roboclawR", 9600)
break;
except SerialException:
rospy.logwarn("Couldn't connect to Left Claw at ttyACM1. trying again .\n Try running 'tty_permission' command")
r_time.sleep()
rospy.loginfo("Connected to Left Claw")
#connected---------------------------------------
#initialising Drive object-------------------
Drive = Drive(rightClaw,leftClaw)
#added self.stop in __init__. Add seperately here if it doesnt work
#------------------------------------------------
#subscriber lines--------------------------------------------------
rospy.Subscriber("/joy",Joy,Drive.drive_callback)
#-------------------------------------------------------------------
#-------------------------------------------------------------------
#updating the received intructions
r_time_f=rospy.Rate(10)
stopped = False
while not rospy.is_shutdown():
if(stopped == False):
Drive.update_steer()
# Drive.update_turn()
stopped = Drive.current_limiter()
else:
print("stopped due to excess current")
rospy.loginfo(Drive.currents)
stopped = True
#rospy.loginfo(Drive.direction)
#rospy.loginfo(Drive.speed)
r_time_f.sleep()
#-------------------------------------------------------------------