refactored some stuff further
This commit is contained in:
@@ -6,13 +6,13 @@ from time import sleep
|
|||||||
|
|
||||||
from .utils import read_config
|
from .utils import read_config
|
||||||
from .imagereaders import NaoImageReader
|
from .imagereaders import NaoImageReader
|
||||||
from .finders import BallFinder
|
from .finders import BallFinder, GoalFinder
|
||||||
from .movements import NaoMover
|
from .movements import NaoMover
|
||||||
|
|
||||||
|
|
||||||
class BallFollower(object):
|
class Striker(object):
|
||||||
|
|
||||||
def __init__(self, nao_ip, nao_port, res, hsv_lower, hsv_upper,
|
def __init__(self, nao_ip, nao_port, res, red_hsv, white_hsv,
|
||||||
min_radius, run_after):
|
min_radius, run_after):
|
||||||
self.mover = NaoMover(nao_ip=nao_ip, nao_port=nao_port)
|
self.mover = NaoMover(nao_ip=nao_ip, nao_port=nao_port)
|
||||||
self.mover.stand_up()
|
self.mover.stand_up()
|
||||||
@@ -20,7 +20,7 @@ class BallFollower(object):
|
|||||||
fps=30, cam_id=0)
|
fps=30, cam_id=0)
|
||||||
self.video_bot = NaoImageReader(nao_ip, port=nao_port, res=res,
|
self.video_bot = NaoImageReader(nao_ip, port=nao_port, res=res,
|
||||||
fps=30, cam_id=1)
|
fps=30, cam_id=1)
|
||||||
self.finder = BallFinder(hsv_lower, hsv_upper, min_radius, None)
|
self.finder = BallFinder(red_hsv[0], red_hsv[1], min_radius, None)
|
||||||
self.lock_counter = 0
|
self.lock_counter = 0
|
||||||
self.loss_counter = 0
|
self.loss_counter = 0
|
||||||
self.run_after = run_after
|
self.run_after = run_after
|
||||||
@@ -103,8 +103,6 @@ class BallFollower(object):
|
|||||||
|
|
||||||
print('moving')
|
print('moving')
|
||||||
increment = 0.1
|
increment = 0.1
|
||||||
# if y < -pi / 8:
|
|
||||||
# self.mover.move_to(-0.1, 0, 0)
|
|
||||||
if y > 0.35:
|
if y > 0.35:
|
||||||
self.mover.move_to(-0.05, 0, 0)
|
self.mover.move_to(-0.05, 0, 0)
|
||||||
elif y < 0.25:
|
elif y < 0.25:
|
||||||
@@ -123,12 +121,12 @@ class BallFollower(object):
|
|||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
|
||||||
cfg = read_config()
|
cfg = read_config()
|
||||||
follower = BallFollower(
|
follower = Striker(
|
||||||
nao_ip=cfg['ip'],
|
nao_ip=cfg['ip'],
|
||||||
nao_port=cfg['port'],
|
nao_port=cfg['port'],
|
||||||
res=cfg['res'],
|
res=cfg['res'],
|
||||||
hsv_lower=tuple(map(cfg.get, ('low_h', 'low_s', 'low_v'))),
|
red_hsv=cfg['red'],
|
||||||
hsv_upper=tuple(map(cfg.get, ('high_h', 'high_s', 'high_v'))),
|
white_hsv=cfg['white'],
|
||||||
min_radius=cfg['min_radius'],
|
min_radius=cfg['min_radius'],
|
||||||
run_after=False
|
run_after=False
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -54,7 +54,8 @@ class Colorpicker(object):
|
|||||||
]
|
]
|
||||||
|
|
||||||
def do_print(self):
|
def do_print(self):
|
||||||
print(self.settings)
|
print(tuple(map(self.settings.get, ('low_h', 'low_s', 'low_v'))),
|
||||||
|
tuple(map(self.settings.get, ('high_h', 'high_s', 'high_v'))))
|
||||||
|
|
||||||
def _on_trackbar(self, val, name, checker):
|
def _on_trackbar(self, val, name, checker):
|
||||||
self.settings[name] = checker(val)
|
self.settings[name] = checker(val)
|
||||||
@@ -63,10 +64,7 @@ class Colorpicker(object):
|
|||||||
def _hsv_updated(self, param):
|
def _hsv_updated(self, param):
|
||||||
cv2.setTrackbarPos(param, self.WINDOW_DETECTION_NAME,
|
cv2.setTrackbarPos(param, self.WINDOW_DETECTION_NAME,
|
||||||
self.settings[param])
|
self.settings[param])
|
||||||
print(param)
|
|
||||||
for marker in self.markers:
|
for marker in self.markers:
|
||||||
print(self.markers[marker])
|
|
||||||
print(self.settings)
|
|
||||||
self.markers[marker].hsv_lower = tuple(
|
self.markers[marker].hsv_lower = tuple(
|
||||||
map(self.settings.get, ('low_h', 'low_s', 'low_v'))
|
map(self.settings.get, ('low_h', 'low_s', 'low_v'))
|
||||||
)
|
)
|
||||||
@@ -94,19 +92,28 @@ class Colorpicker(object):
|
|||||||
cv2.imshow(self.WINDOW_DETECTION_NAME, frame_threshold)
|
cv2.imshow(self.WINDOW_DETECTION_NAME, frame_threshold)
|
||||||
return cv2.waitKey(1)
|
return cv2.waitKey(1)
|
||||||
|
|
||||||
def save(self, filename):
|
def save(self, filename, color):
|
||||||
try:
|
try:
|
||||||
with open(filename) as f:
|
with open(filename) as f:
|
||||||
conf = json.load(f)
|
conf = json.load(f)
|
||||||
except IOError:
|
except IOError:
|
||||||
conf = {}
|
conf = {}
|
||||||
conf.update(self.settings)
|
conf.update(
|
||||||
|
{color:
|
||||||
|
[list(map(self.settings.get, ['low_h', 'low_s', 'low_v'])),
|
||||||
|
list(map(self.settings.get, ['high_h', 'high_s', 'high_v']))]
|
||||||
|
}
|
||||||
|
)
|
||||||
with open(filename, 'w') as f:
|
with open(filename, 'w') as f:
|
||||||
json.dump(conf, f, indent=4)
|
json.dump(conf, f, indent=4)
|
||||||
|
|
||||||
def load(self, filename):
|
def load(self, filename, color):
|
||||||
with open(filename) as f:
|
with open(filename) as f:
|
||||||
self.settings = json.load(f)
|
jdict = json.load(f)
|
||||||
|
self.settings = dict(
|
||||||
|
zip(['low_h', 'low_s', 'low_v', 'high_h', 'high_s', 'high_v'],
|
||||||
|
jdict[color][0] + jdict[color][1])
|
||||||
|
)
|
||||||
for name in self.settings:
|
for name in self.settings:
|
||||||
self._hsv_updated(name)
|
self._hsv_updated(name)
|
||||||
|
|
||||||
@@ -167,11 +174,16 @@ if __name__ == '__main__':
|
|||||||
type=int,
|
type=int,
|
||||||
default=640
|
default=640
|
||||||
)
|
)
|
||||||
|
parser.add_argument(
|
||||||
|
'--color',
|
||||||
|
help='specify which color is being calibrated',
|
||||||
|
default='white'
|
||||||
|
)
|
||||||
args = parser.parse_args()
|
args = parser.parse_args()
|
||||||
|
|
||||||
cp = Colorpicker(['goal'])
|
cp = Colorpicker()
|
||||||
if args.input_config:
|
if args.input_config:
|
||||||
cp.load(args.input_config)
|
cp.load(args.input_config, args.color)
|
||||||
|
|
||||||
if args.video_file:
|
if args.video_file:
|
||||||
rdr = VideoReader(args.video_file, loop=True)
|
rdr = VideoReader(args.video_file, loop=True)
|
||||||
@@ -199,6 +211,6 @@ if __name__ == '__main__':
|
|||||||
finally:
|
finally:
|
||||||
cp.do_print()
|
cp.do_print()
|
||||||
if args.output_config:
|
if args.output_config:
|
||||||
cp.save(args.output_config)
|
cp.save(args.output_config, args.color)
|
||||||
if not args.still:
|
if not args.still:
|
||||||
rdr.close()
|
rdr.close()
|
||||||
|
|||||||
@@ -8,10 +8,10 @@ from .finders import BallFinder
|
|||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
video = VideoReader(0, loop=True)
|
video = VideoReader(0, loop=True)
|
||||||
hsv = read_config()
|
cfg = read_config()
|
||||||
hsv_lower = tuple(map(hsv.get, ('low_h', 'low_s', 'low_v')))
|
hsv_lower = cfg['red'][0]
|
||||||
hsv_upper = tuple(map(hsv.get, ('high_h', 'high_s', 'high_v')))
|
hsv_upper = cfg['red'][1]
|
||||||
finder = BallFinder(hsv_lower, hsv_upper, hsv['min_radius'], None)
|
finder = BallFinder(hsv_lower, hsv_upper, cfg['min_radius'], None)
|
||||||
try:
|
try:
|
||||||
while True:
|
while True:
|
||||||
frame = video.get_frame()
|
frame = video.get_frame()
|
||||||
|
|||||||
@@ -1,7 +1,6 @@
|
|||||||
from __future__ import division
|
from __future__ import division
|
||||||
from __future__ import print_function
|
from __future__ import print_function
|
||||||
|
|
||||||
import json
|
|
||||||
from collections import deque
|
from collections import deque
|
||||||
|
|
||||||
import cv2
|
import cv2
|
||||||
@@ -34,12 +33,11 @@ class GoalFinder(object):
|
|||||||
|
|
||||||
# Final similarity score is just the sum of both
|
# Final similarity score is just the sum of both
|
||||||
final_score = shape_sim + area_sim
|
final_score = shape_sim + area_sim
|
||||||
print(shape_sim, area_sim, final_score)
|
print('Goal:', shape_sim, area_sim, final_score)
|
||||||
return final_score
|
return final_score
|
||||||
|
|
||||||
def find_goal_contour(self, frame):
|
def find_goal_contour(self, frame):
|
||||||
hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
|
hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
|
||||||
print(self.hsv_lower, self.hsv_upper)
|
|
||||||
thr = cv2.inRange(hsv, self.hsv_lower, self.hsv_upper)
|
thr = cv2.inRange(hsv, self.hsv_lower, self.hsv_upper)
|
||||||
|
|
||||||
# The ususal
|
# The ususal
|
||||||
@@ -70,8 +68,8 @@ class GoalFinder(object):
|
|||||||
|
|
||||||
similarities = [self.goal_similarity(cnt) for cnt in good_cnts]
|
similarities = [self.goal_similarity(cnt) for cnt in good_cnts]
|
||||||
best = min(similarities)
|
best = min(similarities)
|
||||||
# if best > 0.4:
|
if best > 0.35:
|
||||||
# return None
|
return None
|
||||||
# Find the contour with the shape closest to that of the goal
|
# Find the contour with the shape closest to that of the goal
|
||||||
goal = good_cnts[similarities.index(best)]
|
goal = good_cnts[similarities.index(best)]
|
||||||
return goal
|
return goal
|
||||||
@@ -87,17 +85,12 @@ class GoalFinder(object):
|
|||||||
|
|
||||||
class BallFinder(object):
|
class BallFinder(object):
|
||||||
|
|
||||||
def __init__(self, hsv_lower, hsv_upper, min_radius, viz=False):
|
def __init__(self, hsv_lower, hsv_upper, min_radius):
|
||||||
|
|
||||||
self.hsv_lower = hsv_lower
|
self.hsv_lower = hsv_lower
|
||||||
self.hsv_upper = hsv_upper
|
self.hsv_upper = hsv_upper
|
||||||
self.min_radius = min_radius
|
self.min_radius = min_radius
|
||||||
self.history = deque(maxlen=64)
|
self.history = deque(maxlen=64)
|
||||||
self.viz = viz
|
|
||||||
|
|
||||||
if self.viz:
|
|
||||||
cv2.namedWindow('ball_mask')
|
|
||||||
cv2.namedWindow('Frame')
|
|
||||||
|
|
||||||
def find_colored_ball(self, frame):
|
def find_colored_ball(self, frame):
|
||||||
hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
|
hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
|
||||||
@@ -152,8 +145,8 @@ class BallFinder(object):
|
|||||||
thickness = int((64 / (i + 1))**0.5 * 2.5)
|
thickness = int((64 / (i + 1))**0.5 * 2.5)
|
||||||
cv2.line(frame, center_now, center_prev, (0, 255, 0), thickness)
|
cv2.line(frame, center_now, center_prev, (0, 255, 0), thickness)
|
||||||
|
|
||||||
def load_hsv_config(self, filename):
|
# def load_hsv_config(self, filename):
|
||||||
with open(filename) as f:
|
# with open(filename) as f:
|
||||||
hsv = json.load(f)
|
# hsv = json.load(f)
|
||||||
self.hsv_lower = tuple(map(hsv.get, ('low_h', 'low_s', 'low_v')))
|
# self.hsv_lower = tuple(map(hsv.get, ('low_h', 'low_s', 'low_v')))
|
||||||
self.hsv_upper = tuple(map(hsv.get, ('high_h', 'high_s', 'high_v')))
|
# self.hsv_upper = tuple(map(hsv.get, ('high_h', 'high_s', 'high_v')))
|
||||||
|
|||||||
@@ -1,173 +0,0 @@
|
|||||||
# This script recognizes the ball in a given video file
|
|
||||||
# python ball_tracking.py --video test3.avi
|
|
||||||
|
|
||||||
# import the necessary packages
|
|
||||||
from collections import deque
|
|
||||||
import numpy as np
|
|
||||||
import argparse
|
|
||||||
import imutils
|
|
||||||
import cv2
|
|
||||||
from time import sleep
|
|
||||||
|
|
||||||
# construct the argument parse and parse the arguments
|
|
||||||
ap = argparse.ArgumentParser()
|
|
||||||
ap.add_argument("-v", "--video",
|
|
||||||
help="path to the (optional) video file")
|
|
||||||
ap.add_argument("-b", "--buffer", type=int, default=64,
|
|
||||||
help="max buffer size")
|
|
||||||
args = vars(ap.parse_args())
|
|
||||||
|
|
||||||
# define the lower and upper boundaries of the "green"
|
|
||||||
# ball in the HSV color space, then initialize the
|
|
||||||
# list of tracked points
|
|
||||||
#greenLower = (0, 17, 225)
|
|
||||||
#greenUpper = (42, 255, 255)
|
|
||||||
|
|
||||||
|
|
||||||
greenLower=(0,184,170)
|
|
||||||
greenUpper=(2,255,255)
|
|
||||||
|
|
||||||
#greenLower = (29, 86, 6)
|
|
||||||
#greenUpper = (64, 255, 255)
|
|
||||||
pts = deque(maxlen=args["buffer"])
|
|
||||||
|
|
||||||
# if a video path was not supplied, grab the reference
|
|
||||||
# to the webcam
|
|
||||||
if not args.get("video", False):
|
|
||||||
camera = cv2.VideoCapture(0)
|
|
||||||
|
|
||||||
# otherwise, grab a reference to the video file
|
|
||||||
else:
|
|
||||||
camera = cv2.VideoCapture(args["video"])
|
|
||||||
|
|
||||||
# keep looping
|
|
||||||
while True:
|
|
||||||
# grab the current frame
|
|
||||||
(grabbed, frame) = camera.read()
|
|
||||||
|
|
||||||
# if we are viewing a video and we did not grab a frame,
|
|
||||||
# then we have reached the end of the video
|
|
||||||
if args.get("video") and not grabbed:
|
|
||||||
break
|
|
||||||
|
|
||||||
# resize the frame, blur it, and convert it to the HSV
|
|
||||||
# color space
|
|
||||||
# frame = imutils.resize(frame, width=600)
|
|
||||||
# blurred = cv2.GaussianBlur(frame, (11, 11), 0)
|
|
||||||
# hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
|
|
||||||
|
|
||||||
# construct a mask for the color "green", then perform
|
|
||||||
# a series of dilations and erosions to remove any small
|
|
||||||
# blobs left in the mask
|
|
||||||
|
|
||||||
'''
|
|
||||||
mask = cv2.inRange(hsv, greenLower, greenUpper)
|
|
||||||
mask = cv2.erode(mask, None, iterations=2)
|
|
||||||
mask = cv2.dilate(mask, None, iterations=2)
|
|
||||||
'''
|
|
||||||
|
|
||||||
# create hsv and do some mask stuff
|
|
||||||
frame_HSV = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
|
|
||||||
# frame_test=cv2.cvtColor(frame_HSV,cv2.COLOR_HSV2BGR)
|
|
||||||
# frame_gray=cv2.cvtColor(frame,cv2.COLOR_BGR2GRAY)
|
|
||||||
|
|
||||||
# frame_threshold=cv2.inRange(frame_HSV,(0,9,139),(180,81,255))
|
|
||||||
frame_threshold=cv2.inRange(frame_HSV,(0,0,182),(180,60,255))
|
|
||||||
|
|
||||||
frame_threshold = cv2.GaussianBlur(frame_threshold,(9,9),3,3)
|
|
||||||
|
|
||||||
erode_element = cv2.getStructuringElement(cv2.MORPH_RECT, (10, 10))
|
|
||||||
#dilate_element = cv2.getStructuringElement(cv2.MORPH_RECT, (20, 20))
|
|
||||||
eroded_mask = cv2.erode(frame_threshold,erode_element)
|
|
||||||
#dilated_mask = cv2.dilate(eroded_mask,dilate_element)
|
|
||||||
#frame_threshold=eroded_mask
|
|
||||||
|
|
||||||
# preparation for edge detection
|
|
||||||
res = cv2.bitwise_and(frame,frame, mask=eroded_mask)
|
|
||||||
res=cv2.cvtColor(res,cv2.COLOR_BGR2GRAY)
|
|
||||||
|
|
||||||
|
|
||||||
# use canny edge
|
|
||||||
frame_edge=cv2.Canny(res,90,494,apertureSize=3)
|
|
||||||
#frame_edge=cv2.Canny(res,0,123,apertureSize=3)
|
|
||||||
|
|
||||||
# use hough lines
|
|
||||||
lines = cv2.HoughLines(frame_edge,1,1*np.pi/180,80,0,0)
|
|
||||||
|
|
||||||
for rho,theta in lines[0]:
|
|
||||||
# print(rho, theta)
|
|
||||||
a = np.cos(theta)
|
|
||||||
b = np.sin(theta)
|
|
||||||
x0 = a*rho
|
|
||||||
y0 = b*rho
|
|
||||||
x1 = int(x0 + 200*(-b))
|
|
||||||
y1 = int(y0 + 200*(a))
|
|
||||||
x2 = int(x0 - 200*(-b))
|
|
||||||
y2 = int(y0 - 200*(a))
|
|
||||||
if (theta>np.pi/180*170 or theta<np.pi/180*10):
|
|
||||||
#if (theta>np.pi/180*80 and theta<np.pi/180*100):
|
|
||||||
cv2.line(frame,(x1,y1),(x2,y2),(0,0,255),2)
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
'''
|
|
||||||
|
|
||||||
# find contours in the mask and initialize the current
|
|
||||||
# (x, y) center of the ball
|
|
||||||
cnts = cv2.findContours(mask.copy(), cv2.RETR_EXTERNAL,
|
|
||||||
cv2.CHAIN_APPROX_SIMPLE)[-2]
|
|
||||||
center = None
|
|
||||||
|
|
||||||
# only proceed if at least one contour was found
|
|
||||||
if len(cnts) > 0:
|
|
||||||
# find the largest contour in the mask, then use
|
|
||||||
# it to compute the minimum enclosing circle and
|
|
||||||
# centroid
|
|
||||||
c = max(cnts, key=cv2.contourArea)
|
|
||||||
((x, y), radius) = cv2.minEnclosingCircle(c)
|
|
||||||
M = cv2.moments(c)
|
|
||||||
center = (int(M["m10"] / M["m00"]), int(M["m01"] / M["m00"]))
|
|
||||||
|
|
||||||
# only proceed if the radius meets a minimum size
|
|
||||||
if radius > 10:
|
|
||||||
# draw the circle and centroid on the frame,
|
|
||||||
# then update the list of tracked points
|
|
||||||
cv2.circle(frame, (int(x), int(y)), int(radius),
|
|
||||||
#(0, 255, 255), 2)
|
|
||||||
(0,255,255),2)
|
|
||||||
cv2.circle(frame, center, 5, (0, 0, 255), -1)
|
|
||||||
|
|
||||||
# update the points queue
|
|
||||||
pts.appendleft(center)
|
|
||||||
|
|
||||||
# loop over the set of tracked points
|
|
||||||
for i in xrange(1, len(pts)):
|
|
||||||
# if either of the tracked points are None, ignore
|
|
||||||
# them
|
|
||||||
if pts[i - 1] is None or pts[i] is None:
|
|
||||||
continue
|
|
||||||
|
|
||||||
# otherwise, compute the thickness of the line and
|
|
||||||
# draw the connecting lines
|
|
||||||
thickness = int(np.sqrt(args["buffer"] / float(i + 1)) * 1.25)
|
|
||||||
cv2.line(frame, pts[i - 1], pts[i], (0, 255, 0), thickness)
|
|
||||||
'''
|
|
||||||
# show the frame to our screen
|
|
||||||
#cv2.imshow("Frame", frame)
|
|
||||||
cv2.imshow("Frame_threshold",frame_threshold)
|
|
||||||
cv2.imshow("eroded_mask",eroded_mask)
|
|
||||||
cv2.imshow("frame edge",frame_edge)
|
|
||||||
cv2.imshow("result eroded_mask applied",res)
|
|
||||||
cv2.imshow("frame with lines",frame)
|
|
||||||
key = cv2.waitKey(1) & 0xFF
|
|
||||||
|
|
||||||
sleep(0.05)
|
|
||||||
# if the 'q' key is pressed, stop the loop
|
|
||||||
if key == ord("q"):
|
|
||||||
break
|
|
||||||
|
|
||||||
# cleanup the camera and close any open windows
|
|
||||||
camera.release()
|
|
||||||
cv2.destroyAllWindows()
|
|
||||||
|
|
||||||
|
|
||||||
@@ -1,14 +1,32 @@
|
|||||||
{
|
{
|
||||||
|
"cam": 1,
|
||||||
"ip": "192.168.0.11",
|
"ip": "192.168.0.11",
|
||||||
"res": 1,
|
"min_radius": 5,
|
||||||
"port": 9559,
|
|
||||||
"cam": 0,
|
|
||||||
"fps": 30,
|
"fps": 30,
|
||||||
"low_s": 175,
|
"res": 1,
|
||||||
"low_v": 100,
|
"white": [
|
||||||
"high_h": 6,
|
[
|
||||||
"high_v": 255,
|
0,
|
||||||
"low_h": 0,
|
0,
|
||||||
"high_s": 255,
|
140
|
||||||
"min_radius": 5
|
],
|
||||||
|
[
|
||||||
|
180,
|
||||||
|
62,
|
||||||
|
255
|
||||||
|
]
|
||||||
|
],
|
||||||
|
"port": 9559,
|
||||||
|
"red": [
|
||||||
|
[
|
||||||
|
0,
|
||||||
|
175,
|
||||||
|
100
|
||||||
|
],
|
||||||
|
[
|
||||||
|
6,
|
||||||
|
255,
|
||||||
|
255
|
||||||
|
]
|
||||||
|
]
|
||||||
}
|
}
|
||||||
@@ -1,60 +0,0 @@
|
|||||||
# -*- encoding: UTF-8 -*-
|
|
||||||
# syntax
|
|
||||||
# python setangles.py x y
|
|
||||||
|
|
||||||
import sys
|
|
||||||
from naoqi import ALProxy
|
|
||||||
import time
|
|
||||||
|
|
||||||
def main(robotIP):
|
|
||||||
PORT = 9559
|
|
||||||
|
|
||||||
try:
|
|
||||||
motionProxy = ALProxy("ALMotion", robotIP, PORT)
|
|
||||||
except Exception,e:
|
|
||||||
print "Could not create proxy to ALMotion"
|
|
||||||
print "Error was: ",e
|
|
||||||
sys.exit(1)
|
|
||||||
|
|
||||||
# activiert gelenke
|
|
||||||
motionProxy.setStiffnesses("Head", 1.0)
|
|
||||||
|
|
||||||
# Example showing how to set angles, using a fraction of max speed
|
|
||||||
names = ["HeadYaw", "HeadPitch"]
|
|
||||||
|
|
||||||
# go into left direction
|
|
||||||
i=0
|
|
||||||
while i<2:
|
|
||||||
angles = [i,0]
|
|
||||||
fractionMaxSpeed =0.5
|
|
||||||
motionProxy.setAngles(names, angles, fractionMaxSpeed)
|
|
||||||
i=float(i)+3.14/4
|
|
||||||
time.sleep(0.3)
|
|
||||||
|
|
||||||
# go back to middle position
|
|
||||||
angles = [0,0]
|
|
||||||
fractionMaxSpeed =0.5
|
|
||||||
motionProxy.setAngles(names, angles, fractionMaxSpeed)
|
|
||||||
print "head set back"
|
|
||||||
time.sleep(0.3)
|
|
||||||
|
|
||||||
# go into the right direction
|
|
||||||
i=0
|
|
||||||
while i > -2:
|
|
||||||
angles = [i,0]
|
|
||||||
fractionMaxSpeed =0.5
|
|
||||||
motionProxy.setAngles(names, angles, fractionMaxSpeed)
|
|
||||||
i=i-3.14/4
|
|
||||||
time.sleep(0.3)
|
|
||||||
|
|
||||||
# go back to middle position
|
|
||||||
angles = [0,0]
|
|
||||||
fractionMaxSpeed =0.5
|
|
||||||
motionProxy.setAngles(names, angles, fractionMaxSpeed)
|
|
||||||
print "head set back"
|
|
||||||
time.sleep(1)
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
|
||||||
robotIp = "192.168.0.11"
|
|
||||||
|
|
||||||
main(robotIp)
|
|
||||||
Reference in New Issue
Block a user