Browse Source

Minimal pose goal

autodock/move_base
hello-chintan 1 year ago
parent
commit
887f863e9f
1 changed files with 32 additions and 3 deletions
  1. +32
    -3
      stretch_navigation/nodes/move_base_pose.py

+ 32
- 3
stretch_navigation/nodes/move_base_pose.py View File

@ -1,8 +1,37 @@
#!/usr/bin/env python3
import rospy
import move_base
from move_base_msgs.msg import MoveBaseActionGoal
from move_base_msgs.msg import MoveBaseActionFeedback
from move_base_msgs.msg import MoveBaseActionResult
import actionlib
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
from geometry_msgs.msg import PoseStamped
def movebase_client():
client = actionlib.SimpleActionClient('move_base', MoveBaseAction)
client.wait_for_server()
goal = MoveBaseGoal()
goal.target_pose.header.frame_id = "map"
goal.target_pose.header.stamp = rospy.Time.now()
goal.target_pose.pose.position.x = 0.5
goal.target_pose.pose.orientation.w = 1.0
client.send_goal(goal)
wait = client.wait_for_result()
if not wait:
rospy.logerr("Action server not available!")
rospy.signal_shutdown("Action server not available!")
else:
return client.get_result()
if __name__ == '__main__':
try:
rospy.init_node('move_base_pose')
result = movebase_client()
if result:
rospy.loginfo("Goal execution done!")
except rospy.ROSInterruptException:
rospy.loginfo("Navigation test finished.")

Loading…
Cancel
Save