Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix nao vision for naoqi 2.5 #13

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
33 changes: 22 additions & 11 deletions nao_vision/nodes/nao_vision.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,8 @@
from nao_interaction_msgs.srv import (
LearnFace,
LearnFaceResponse,
VisionMotionSensitivity)
VisionMotionSensitivity,
VisionMotionSensitivityResponse)

class Constants:
NODE_NAME = "nao_vision_interface"
Expand Down Expand Up @@ -287,70 +288,80 @@ def onFaceDetected(self, strVarName, value, strMessage):
self.facesPub.publish(self.faces)

def handleSensitivityChangeSrv(self, req):
res = VisionMotionSensitivityResponse()
if (req.sensitivity.data < 0.0) or (req.sensitivity.data > 1.0):
return
return res

self.movementDetectionProxy.setSensitivity(req.sensitivity.data)
rospy.loginfo("Sensitivity of nao_movement_detection changed to %f", req.sensitivity.data)
return res

def onMovementDetected(self, strVarName, value, strMessage):
"Called when movement was detected"
datavar = self.memProxy.getData("MovementDetection/MovementInfo")
if len(datavar) <= 0:
return

movement = MovementDetected()

movement.gravity_center.x = datavar[0][0][0]
movement.gravity_center.y = datavar[0][0][1]
movement.gravity_center.x = datavar[1][0][0][0]
movement.gravity_center.y = datavar[1][0][0][1]

movement.mean_velocity.x = datavar[0][1][0]
movement.mean_velocity.y = datavar[0][1][1]
movement.mean_velocity.x = 0
movement.mean_velocity.y = 0

for i in range(0, len(datavar[0][2])):
if len(datavar[1][0]) >= 5:
movement.points_poses.append(Point())
movement.points_poses[i].x = datavar[0][2][i][0]
movement.points_poses[i].y = datavar[0][2][i][1]
movement.points_poses[0].x = datavar[1][0][5][0]
movement.points_poses[0].y = datavar[1][0][5][1]

movement.points_speeds.append(Point())
movement.points_speeds[i].x = datavar[0][3][i][0]
movement.points_speeds[i].y = datavar[0][3][i][1]
movement.points_speeds[0].x = 0
movement.points_speeds[0].y = 0

self.movementPub.publish(movement)

def serveSubscribeFaceSrv(self, req):
self.facesPub = rospy.Publisher("nao_vision/faces_detected", FaceDetected)
self.memProxy.subscribeToEvent("FaceDetected", self.moduleName, "onFaceDetected")
self.face_detection_enabled = True
return EmptyResponse()

def serveUnsubscribeFaceSrv(self, req):
if self.face_detection_enabled:
self.memProxy.unsubscribeToEvent("FaceDetected", self.moduleName)
self.facesPub.unregister()
self.face_detection_enabled = False
return EmptyResponse()

def serveSubscribeMotionSrv(self, req):
self.movementPub = rospy.Publisher("nao_vision/movement_detected", MovementDetected)
self.sensitivitySrv = rospy.Service("nao_vision/movement_detection_sensitivity", VisionMotionSensitivity, self.handleSensitivityChangeSrv )
self.memProxy.subscribeToEvent("MovementDetection/MovementDetected", self.moduleName, "onMovementDetected")
self.motion_detection_enabled = True
return EmptyResponse()

def serveUnsubscribeMotionSrv(self, req):
if self.motion_detection_enabled:
self.memProxy.unsubscribeToEvent("MovementDetection/MovementDetected", self.moduleName)
self.movementPub.unregister()
self.sensitivitySrv.shutdown()
self.motion_detection_enabled = False
return EmptyResponse()

def serveSubscribeLandmarkSrv(self, req):
self.landmarkPub = rospy.Publisher("nao_vision/landmark_detected", LandmarkDetected)
self.memProxy.subscribeToEvent("LandmarkDetected", self.moduleName, "onLandmarkDetected")
self.landmarkDetectionProxy.updatePeriod("ROSNaoVisionModuleLandmarkDetected", 200)
self.landmark_detection_enabled = True
return EmptyResponse()

def serveUnsubscribeLandmarkSrv(self, req):
if self.landmark_detection_enabled:
self.memProxy.unsubscribeToEvent("LandmarkDetected", self.moduleName)
self.landmarkPub.unregister()
self.landmark_detection_enabled = False
return EmptyResponse()

def learnFaceSrv(self, req):
res = LearnFaceResponse()
Expand Down