naoqi_moveto.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (C) 2014 Aldebaran Robotics
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #     http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 #
00017 #import ROS dependencies
00018 import rospy
00019 
00020 #import NAO dependencies
00021 from naoqi_driver.naoqi_node import NaoqiNode
00022 from geometry_msgs.msg import PoseStamped
00023 from geometry_msgs.msg import Pose
00024 import almath
00025 import tf
00026 from tf.transformations import euler_from_quaternion
00027 
00028 class MoveToListener(NaoqiNode):
00029 
00030     def __init__(self):
00031         NaoqiNode.__init__(self, 'naoqi_moveto_listener')
00032         self.connectNaoQi()
00033         self.listener = tf.TransformListener()
00034 
00035         self.subscriber = rospy.Subscriber("/move_base_simple/goal", PoseStamped, self.callback)
00036 
00037     # (re-) connect to NaoQI:
00038     def connectNaoQi(self):
00039         rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00040 
00041         self.motionProxy = self.get_proxy("ALMotion")
00042         if self.motionProxy is None:
00043             exit(1)
00044 
00045     def callback(self, poseStamped):
00046         # reset timestamp because of bug: https://github.com/ros/geometry/issues/82
00047         poseStamped.header.stamp = rospy.Time(0)
00048         try:
00049             robotToTarget1 = self.listener.transformPose("/base_footprint", poseStamped)
00050         except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException) as e:
00051             rospy.logerr("Error while transforming pose: %s", str(e))
00052             return
00053         quat = robotToTarget1.pose.orientation
00054         (roll,pitch,yaw) = euler_from_quaternion((quat.x, quat.y, quat.z, quat.w))
00055         self.motionProxy.moveTo(robotToTarget1.pose.position.x, robotToTarget1.pose.position.y, yaw)


naoqi_driver
Author(s): Armin Hornung, Armin Hornung, Stefan Osswald, Daniel Maier, Miguel Sarabia, Severin Lemaignan
autogenerated on Fri Jul 3 2015 12:51:45