corrected_initialpose.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Maps the initialpose pointing to Nao's torso to a corrected pose with correct 
00004 # height.
00005 #
00006 # Author: Johannes Garimort
00007 # License: BSD
00008 
00009 import roslib
00010 roslib.load_manifest('footstep_planner')
00011 import rospy
00012 import geometry_msgs.msg as geo_msgs
00013 
00014 def callback(pose, pub):
00015     newpose = pose
00016     newpose.pose.pose.position.z += 0.315
00017     pub.publish(newpose)
00018 
00019 def listener():
00020     rospy.init_node('corrected_initialpose')
00021     pub = rospy.Publisher('nao_corrected_initialpose', 
00022                           geo_msgs.PoseWithCovarianceStamped)
00023     rospy.Subscriber("initialpose", geo_msgs.PoseWithCovarianceStamped, 
00024                      callback, pub)
00025     rospy.spin()
00026 
00027 if __name__ == '__main__':
00028     try:
00029         listener()
00030     except rospy.ROSInterruptException: pass


bipedRobin_footstep_planner
Author(s):
autogenerated on Fri Nov 15 2013 11:11:28