src/naoqi_driver/naoqi_moveto.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (C) 2014 Aldebaran Robotics
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 #
17 #import ROS dependencies
18 import rospy
19 
20 #import NAO dependencies
21 from naoqi_driver.naoqi_node import NaoqiNode
22 from geometry_msgs.msg import PoseStamped
23 from geometry_msgs.msg import Pose
24 from geometry_msgs.msg import Twist
25 import almath
26 import tf
27 from tf.transformations import euler_from_quaternion
28 
30 
31  def __init__(self):
32  NaoqiNode.__init__(self, 'naoqi_moveto_listener')
33  self.connectNaoQi()
34  self.listener = tf.TransformListener()
35 
36  self.goal_sub = rospy.Subscriber('move_base_simple/goal', PoseStamped, self.goalCB)
37  self.cvel_sub = rospy.Subscriber('cmd_vel', Twist, self.cvelCB)
38 
39 
40  # (re-) connect to NaoQI:
41  def connectNaoQi(self):
42  rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
43 
44  self.motionProxy = self.get_proxy("ALMotion")
45  if self.motionProxy is None:
46  exit(1)
47 
48  def goalCB(self, poseStamped):
49  # reset timestamp because of bug: https://github.com/ros/geometry/issues/82
50  poseStamped.header.stamp = rospy.Time(0)
51  try:
52  robotToTarget1 = self.listener.transformPose("/base_footprint", poseStamped)
53  except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException) as e:
54  rospy.logerr("Error while transforming pose: %s", str(e))
55  return
56  quat = robotToTarget1.pose.orientation
57  (roll,pitch,yaw) = euler_from_quaternion((quat.x, quat.y, quat.z, quat.w))
58  self.motionProxy.moveTo(robotToTarget1.pose.position.x, robotToTarget1.pose.position.y, yaw)
59 
60  def cvelCB(self, twist):
61  rospy.logdebug("cmd_vel: %f %f %f", twist.linear.x, twist.linear.y, twist.angular.z)
62  eps = 1e-3 # maybe 0,0,0 is a special command in motionProxy...
63  if abs(twist.linear.x)<eps and abs(twist.linear.y)<eps and abs(twist.angular.z)<eps:
64  self.motionProxy.moveToward(0,0,0)
65  else:
66  self.motionProxy.moveToward(twist.linear.x, twist.linear.y, twist.angular.z)
def get_proxy(self, name, warn=True)
Definition: naoqi_node.py:128


naoqi_driver_py
Author(s): Armin Hornung, Armin Hornung, Stefan Osswald, Daniel Maier, Miguel Sarabia, Severin Lemaignan
autogenerated on Thu Jul 16 2020 03:18:30