Skip to content

Commit

Permalink
Add files via upload
Browse files Browse the repository at this point in the history
  • Loading branch information
Zorrotoro authored Aug 24, 2020
1 parent bcff1a6 commit 3229b81
Show file tree
Hide file tree
Showing 5 changed files with 353 additions and 0 deletions.
11 changes: 11 additions & 0 deletions Readme.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
1. Open Terminal sourcing the turtlebot2 and run the Gazebo simulation world
2. Open a new terminal and source the turtlebot2
3. Extract the image.py and locomotion.py on the working directory
4. check the terminal 2 working directory is same the launch file
5. run python code locomotion.py "python locomotion.py"
6. Gazebo Turtlebot will start navigating
7. Respective datalogs will get produced in the same directory under the file name datalogging
8. Obstacles photo will be taken and stored on the same working directory


*** Note: This code is unmonitored and will not be updated ***
Binary file added Report.pdf
Binary file not shown.
65 changes: 65 additions & 0 deletions image.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
from __future__ import print_function
import sys
import rospy
import cv2
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError


x=2

class TakePhoto:
def __init__(self):

self.bridge = CvBridge()
self.image_received = False

# Connect image topic
img_topic = "/camera/rgb/image_raw"
self.image_sub = rospy.Subscriber(img_topic, Image, self.callback)

# Allow up to one second to connection
rospy.sleep(1)

def callback(self, data):

# Convert image to OpenCV format
try:
cv_image = self.bridge.imgmsg_to_cv2(data, "bgr8")
except CvBridgeError as e:
print(e)

self.image_received = True
self.image = cv_image

def take_picture(self, img_title):
if self.image_received:
# Save an image
cv2.imwrite(img_title, self.image)


return True
else:
return False

if __name__ == '__main__':

# Initialize
rospy.init_node('take_photo', anonymous=False)
camera = TakePhoto()

# Take a photo

# Use '_image_title' parameter from command line
# Default value is 'obstacle.jpg'
img_title = rospy.get_param('~image_title', 'obstacle.jpg')
x+=x

if camera.take_picture(img_title):
rospy.loginfo("Saved image " + img_title)
else:
rospy.loginfo("No images received")

# Sleep to give the last log messages time to be sent
rospy.sleep(1)
254 changes: 254 additions & 0 deletions locomotion.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,254 @@
from image import *
import rospy
from geometry_msgs.msg import Twist
from kobuki_msgs.msg import BumperEvent
from std_msgs.msg import Float64


##Global Variables Declaration

g=0
y=0
z=0
q=0
bump = False
bumpRight = False
leftTurn= False
uturnflag=False
image=1
cmd_vel = rospy.Publisher('cmd_vel_mux/input/navi', Twist, queue_size=10)
file=open("datalogging.txt",'a+')


##Function block for obstacle identification

def processBump(data):
print("bump")
global bump

bump = False


if data.state==BumperEvent.PRESSED and bumpRight:


uturn(325)



elif data.state==BumperEvent.PRESSED and not bumpRight:
print("stuck")

bump = True

else:
bump = False





###############################################
#####Moves to opposite side of wall when endpoint reached

def uturn(throw):

global move_cmd
global uturnflag
uturnflag=True
move_cmd= Twist()
degree=throw
global image
global file
t=0
while t<10:
move_cmd.linear.x = -0.4
move_cmd.angular.z =0
file.write("linear=-0.4, angular=0\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
t+=1
r.sleep()
rospy.loginfo(t)
camera = TakePhoto()
img_title = rospy.get_param('~image_title', 'obstacle_%s.jpg'%image)
image+=image
camera.take_picture(img_title)
t=0
while degree>0:
move_cmd.linear.x = 0
move_cmd.angular.z =-0.2
file.write("linear=0, angular=-0.2\n")
rospy.loginfo(degree)
left_move_little()

def left_move_little():
global leftTurn
global uturnflag
global file

if not leftTurn:
leftTurn = True
s=0
t=0

while t<50:
move_cmd.linear.x = 0.3
move_cmd.angular.z =0
file.write("linear=0.3, angular=0\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
t+=1
r.sleep()
rospy.loginfo(t)
t=0
while t<150:
move_cmd.linear.x = 0
move_cmd.angular.z =-0.2
file.write("linear=0, angular=-0.2\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
t+=1
r.sleep()
t=0

uturnflag=False
leftTurn = False


#########################################################
## Avoids the obstacles when encountered



def turn(throw):
print("exe")
global q,g
global move_cmd
move_cmd= Twist()
degree=throw
g=throw
global image
global file
while q<10:
move_cmd.linear.x = -0.4
move_cmd.angular.z =0
file.write("linear=-0.4, angular=0\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
q+=1
r.sleep()
rospy.loginfo(q)

camera = TakePhoto()
img_title = rospy.get_param('~image_title', 'obstacle_%s.jpg'%image)
image+=image
camera.take_picture(img_title)
q=0
while degree>0:
move_cmd.linear.x = 0
move_cmd.angular.z =-0.2
file.write("linear=0, angular=-0.2\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
degree-=1
r.sleep()
rospy.loginfo(degree)
move_little()

def move_little():
global y
global move_cmd
global bumpRight
global file
move_cmd= Twist()
if not bumpRight:
while y<25 and not uturnflag:
bumpRight = True
move_cmd.linear.x = 0.3
move_cmd.angular.z =0
file.write("linear=0.3, angular=0\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
y+=1
r.sleep()
rospy.loginfo(y)



y=0
bumpRight = False
turn_back()


def turn_back():
global g
global move_cmd
move_cmd= Twist()
global file
if not bumpRight:

while g>0 and not uturnflag:
move_cmd.linear.x = 0
move_cmd.angular.z =0.2
file.write("linear=0.2, angular=0.2\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
g-=1
r.sleep()
rospy.loginfo(g)


# Shutdown function

def shutdown():
# stop turtlebot
rospy.loginfo("Stop TurtleBot")
# a default Twist has linear.x of 0 and angular.z of 0. So it'll stop TurtleBot
file.close()
cmd_vel.publish(Twist())


# Main Function - Turtlebot moves

def listener():
rospy.init_node('laserscan', anonymous=True)
print("listen")
global cmd_vel
global file
sub=rospy.Subscriber('mobile_base/events/bumper', BumperEvent, processBump)
# spin() simply keeps python from exiting until this node is stopped
rospy.on_shutdown(shutdown)
print("run")
move_cmd= Twist()
move_cmd.linear.x = 0.3
move_cmd.angular.z =0


while not rospy.is_shutdown():


if not uturnflag:


global bump
global bumpRight
if bumpRight:
bumpRight=False
if bump==True:
print("turn")
turn(150)
print("running")
file.write("linear=0.3, angular=0\n")
cmd_vel.publish(move_cmd)
r = rospy.Rate(20)
r.sleep()


if __name__ == '__main__':
try:
print("start")
listener()
except Exception as e:
print(e)
rospy.loginfo("GoForward node terminated.")
23 changes: 23 additions & 0 deletions overview.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
######## List of nodes and its descriptions############


#1 rospy -> Python client library for ROS
This enables the python code implementation



#2 Twist -> Node under the nodetopic geometry_msgs.msg

Twist node manages the velocity of the Turtlebot. It can control both the linear and angular velocity of the robot


#3 BumperEvent ->Node under the nodetopic kobuki_msgs.msg

This gives the feedback based upon the bumper contact switching of the turtlebot


#4 Image -> Node under the nodetopic sensor_msgs.msg

Pictures taken by using the /camera/rgb/image_raw sensors.


0 comments on commit 3229b81

Please sign in to comment.