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 from geometry_msgs.msg import Twist
00025 import almath
00026 import tf
00027 from tf.transformations import euler_from_quaternion
00028 
00029 class MoveToListener(NaoqiNode):
00030 
00031     def __init__(self):
00032         NaoqiNode.__init__(self, 'naoqi_moveto_listener')
00033         self.connectNaoQi()
00034         self.listener = tf.TransformListener()
00035 
00036         self.goal_sub = rospy.Subscriber('move_base_simple/goal', PoseStamped, self.goalCB)
00037         self.cvel_sub = rospy.Subscriber('cmd_vel', Twist, self.cvelCB)
00038 
00039 
00040     # (re-) connect to NaoQI:
00041     def connectNaoQi(self):
00042         rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00043 
00044         self.motionProxy = self.get_proxy("ALMotion")
00045         if self.motionProxy is None:
00046             exit(1)
00047 
00048     def goalCB(self, poseStamped):
00049         # reset timestamp because of bug: https://github.com/ros/geometry/issues/82
00050         poseStamped.header.stamp = rospy.Time(0)
00051         try:
00052             robotToTarget1 = self.listener.transformPose("/base_footprint", poseStamped)
00053         except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException) as e:
00054             rospy.logerr("Error while transforming pose: %s", str(e))
00055             return
00056         quat = robotToTarget1.pose.orientation
00057         (roll,pitch,yaw) = euler_from_quaternion((quat.x, quat.y, quat.z, quat.w))
00058         self.motionProxy.moveTo(robotToTarget1.pose.position.x, robotToTarget1.pose.position.y, yaw)
00059 
00060     def cvelCB(self, twist):
00061         rospy.logdebug("cmd_vel: %f %f %f", twist.linear.x, twist.linear.y, twist.angular.z)
00062         eps = 1e-3 # maybe 0,0,0 is a special command in motionProxy...
00063         if abs(twist.linear.x)<eps and abs(twist.linear.y)<eps and abs(twist.angular.z)<eps:
00064             self.motionProxy.moveToward(0,0,0)
00065         else:
00066             self.motionProxy.moveToward(twist.linear.x, twist.linear.y, twist.angular.z)


naoqi_driver_py
Author(s): Armin Hornung, Armin Hornung, Stefan Osswald, Daniel Maier, Miguel Sarabia, Severin Lemaignan
autogenerated on Wed Aug 16 2017 02:28:07