Skip to content

Commit

Permalink
added scripts to show cam feed from left arm,and move left arm to hov…
Browse files Browse the repository at this point in the history
…er above table
  • Loading branch information
swiz23 committed Nov 22, 2017
1 parent 4fd3da0 commit 2530df1
Show file tree
Hide file tree
Showing 4 changed files with 151 additions and 0 deletions.
43 changes: 43 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
# Misc #
########
*~
*TAGS

# Compiled source #
###################
*.com
*.class
*.dll
*.exe
*.o
*.so
*.pyc

# Packages #
############
# it's better to unpack these files and commit the raw source
# git has its own built in compression methods
*.7z
*.dmg
*.gz
*.iso
*.jar
*.rar
*.tar
*.zip

# Logs and databases #
######################
*.log
*.sql
*.sqlite

# OS generated files #
######################
.DS_Store?
ehthumbs.db
Icon?
Thumbs.db

# Project specific files #
##########################
13 changes: 13 additions & 0 deletions launch/baxter_sw.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<launch>

<!-- Open baxter's right hand camera and set the required resolution -->

<node pkg="baxter_tools" type="enable_robot.py" name="enable_robot" args="-e" />

<node pkg="baxter_tools" type="camera_control.py" name="open_left_camera" output="screen" args="-o left_hand_camera -r 1280x800" />

<node name="starbax" pkg="starbax" type="starbax_sw.py"> </node>

<node name="table_cam" pkg="starbax" type="table_cam_sw.py"> </node>

</launch>
27 changes: 27 additions & 0 deletions src/starbax_sw.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
#!/usr/bin/env python
import rospy
from math import pi
import baxter_interface

# def main():
rospy.init_node('initial')
# Define your image topic

limb = baxter_interface.Limb('left')
angles = limb.joint_angles()

angles['left_s0']=-pi/4
angles['left_s1']=-pi/4
angles['left_e0']=0.0
angles['left_e1']=pi/4
angles['left_w0']=0.0
angles['left_w1']=90*pi/180
angles['left_w2']=pi

limb.move_to_joint_positions(angles)




# if __name__ == '__main__':
# main()
68 changes: 68 additions & 0 deletions src/table_cam_sw.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
#!/usr/bin/env python
import rospy
import numpy as np
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import cv2
from matplotlib import pyplot as plt

class starbaxHome:

def __init__(self):

self.bridge = CvBridge()
image_topic = "/cameras/left_hand_camera/image"
self.sb = rospy.Subscriber(image_topic, Image, self.image_callback)
self.gotMask = False
def image_callback(self,msg):

# Convert your ROS Image message to OpenCV2
table = self.bridge.imgmsg_to_cv2(msg, "bgr8")
cv2.waitKey(3)
hsv_frame = cv2.cvtColor(table, cv2.COLOR_BGR2HSV)
if self.gotMask == True:
self.Mask = cv2.inRange(hsv_frame,self.lower,self.upper)
table = cv2.bitwise_and(table,table,mask=self.Mask)
else:
self.gotMask = True
hist_maskH = cv2.calcHist([hsv_frame],[0],None,[180],[0,180])
hist_maskS = cv2.calcHist([hsv_frame],[1],None,[256],[0,256])
flipH = (hist_maskH[::-1].copy())
flipS = (hist_maskS[::-1].copy())
index = np.where(max(hist_maskH))
start = 0
end = 0
if index >= 80:
start = 80
else:
end = 80
print 'greater'
l_h = np.argmax(hist_maskH[start:]>max(hist_maskH)*.02) + start
l_s = np.argmax(hist_maskS>max(hist_maskS)*.02)
u_h = 180 - (np.argmax(flipH[end:]>max(flipH)*.02)+end)
u_s = 256 - np.argmax(flipS>max(flipS)*.02)
print l_h,l_s,u_h,u_s
# plt.figure('histogram')
# plt.subplot(211)
# plt.plot(hist_maskH,'r')
# plt.subplot(212)
# plt.plot(hist_maskS,'g')
# plt.show()
self.lower = np.array([0,l_s,0],np.uint8)
self.upper = np.array([30,u_s,255],np.uint8)

cv2.imshow('table',table)


def main():

ic = starbaxHome()
rospy.init_node('table_cam')

try:
rospy.spin()
except KeyboardInterrupt:
cv2.destroyAllWindows()

if __name__ == '__main__':
main()

0 comments on commit 2530df1

Please sign in to comment.