Skip to content
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
106 changes: 106 additions & 0 deletions Drive System/sub joynode pub roverdrive
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Joy
from geometry_msgs.msg import Point
from numpy import interp


#if turned on the direction is reversed

pwm=[0,0,0]

point = Point()


def find_pwmtest3(msg):
'''dir_n = 0

pwm[2] = dir_n
pwmtotal=interp(msg.axes[2],[-1,1],[-255,255])

if (pwmtotal < 0):
dir_n = 1
pwm[2] = dir_n
pwmtotal=pwmtotal*-1
if (msg.buttons[4] == 1):
pwm[0]=pwmtotal
if (msg.buttons[4] == 0):
pwm[0]=0
if (msg.buttons[5] == 1):
pwm[1]=pwmtotal
if (msg.buttons[5] == 0):
pwm[1]=0
'''
pwmtotal=interp(msg.axes[1],[-1,1],[-255,255])
pwmdir=interp(msg.axes[2],[-1,1],[-155,155])
pwm[2]=0
if(pwmtotal<0):
pwm[2]=1
pwmtotal=pwmtotal*-1
if(pwmdir>=0):
pwm[0]=pwmtotal-pwmdir
pwm[1]=0
if(pwmdir<0):
pwm[0]=0
pwm[1]=pwmtotal+pwmdir
#rospy.loginfo("left pwm %f",pwm[0])
#rospy.loginfo("right pwm %f",pwm[1])
rospy.loginfo(pwm)

def find_pwmtest2(msg):
dir_n = 0

pwm[2] = dir_n
pwmtotal=interp(msg.axes[2],[-1,1],[-255,255])

if (pwmtotal < 0):
dir_n = 1
pwm[2] = dir_n
pwmtotal=pwmtotal*-1
if (msg.buttons[4] == 1):
pwm[0]=pwmtotal
if (msg.buttons[4] == 0):
pwm[0]=0
if (msg.buttons[5] == 1):
pwm[1]=pwmtotal
if (msg.buttons[5] == 0):
pwm[1]=0

#rospy.loginfo("left pwm %f",pwm[0])
#rospy.loginfo("right pwm %f",pwm[1])
rospy.loginfo(pwm)


def find_pwmtest1(msg): #1st case when 2 pwm valus are send for left ans right seperately
pwm=[0,0]
valL= msg.axes[1]
valR= msg.axes[2]
pwm[0]=interp(valL,[0,1],[0,255])
pwm[1]=interp(valR,[0,1],[0,255])
rospy.loginfo("left pwm %f",pwm[0])
rospy.loginfo("right pwm %f",pwm[1])

def transform(a):
point.x = pwm[0]
point.y = pwm[1]
point.z = pwm[2]

def callback(msg):
rate = rospy.Rate(100)
find_pwmtest3(msg)
point.x = pwm[0]
point.y = pwm[1]
point.z = pwm[2]
pub = rospy.Publisher('rover_drive', Point ,queue_size=100)
pub.publish(point)
rate.sleep()
#rospy.loginfo("I heard %f",msg.buttons[])


def listener():
rospy.init_node('listener_joy', anonymous=True)
rospy.Subscriber("joy", Joy, callback)
rospy.spin()

if __name__ == '__main__':
listener()
44 changes: 44 additions & 0 deletions Drive System/sub roverdrive and sending serialcom to arduino
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
#!/usr/bin/env python
import rospy
from geometry_msgs.msg import Point
import serial
import time

arduino = serial.Serial('/dev/ttyACM0', 9600, timeout=.1)


def callback(data):
valL=data.x
if (valL == 0.0):
valL=str("000")
else:
valL=str(int(valL))

valR=data.y
if (valR == 0.0):
valR=str("000")
else:
valR=str(int(valR))

valD=data.z
if (valD == 0.0):
valD=str("0")
else:
valD=str(int(valD))

val= valL + " " + valR + " " + valD + " " + '\0'

rospy.loginfo(val)
arduino.write(val)

def listener():

rospy.init_node('pwmreciver', anonymous=True)

rospy.Subscriber("rover_drive", Point , callback)

rospy.spin()

if __name__ == '__main__':
listener()

56 changes: 56 additions & 0 deletions arduino code for serialcom
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@

int data;
long unsigned int totaldata;
char dataL[4],dataR[4], dataD[4];
void setup() {
Serial.begin(9600);
pinMode(9,OUTPUT);
pinMode(8,OUTPUT);
pinMode(10,OUTPUT);
}
void loop() {
if(Serial.available() > 0) {
char buffer[] = {' ',' ',' ',' ',' ',' ',' ',' ',' ',' ',' ',' ',' '}; // Receive up to 10 bytes
while (!Serial.available()); // Wait for characters
Serial.readBytesUntil('\0', buffer, 14);
int x=0,i=0,j=0,y=0,val3=0;
while(buffer[i]!=' ')
{
dataL[x]=buffer[i];
i++;
x++;
}
dataL[x]='\0';
i++;

while(buffer[i]!=' ')
{
dataR[j]=buffer[i];
i++;
j++;
}
dataR[j]='\0';
i++;
if(buffer[i]=='1')
val3=1;

int val1 = atoi(dataL);
int val2 = atoi(dataR);

//dataD=totaldata%1000;
//totaldata

val1=(int(val1/10))*10;
val2=(int(val2/10))*10;

Serial.print(val1);
Serial.print(",");
Serial.print(val2);
Serial.print("'");
Serial.println(val3);
analogWrite(9,val1);
analogWrite(10,val2);
digitalWrite(8,val3);
}

}
Loading