Yes, you can send the goal pose using the MoveBaseGoal message type to the MoveBaseAction server in the namespace /move_base
. But before sending the goal you will need to have the FUNMAP generated MHI (Maximum Height Image) Map available in the topic /map
so that you can send your goal pose in the map’s frame.
Generating the Map using FUNMAP Headscan Service
- Launch the FUNMAP node along with Stretch Driver, D435i and other necessary nodes. For this you can launch the stretch_driver.launch and the mapping.launch.
# Terminal 1
roslaunch stretch_core stretch_driver.launch
# Terminal 2
roslaunch stretch_funmap mapping.launch
- Perform a Headscan by calling the service
/funmap/trigger_head_scan
which will make robot head rotate around from two different base rotated positions. It would take few seconds for processing of the 3D MHI map to complete. This would be visualized in through Rviz. (rviz file)
rosservice call /funmap/trigger_head_scan
The final output would look something similar below
(Source)
The Rviz Visualization will look similar to below image:
For sending a MoveBase Goal you could either use the “2D Nav Goal” feature in the Rviz to set a goal pose on the generated map or you can programmatically send a goal pose by creating a Movebase Action client at the namespace /move_base
. The robot should be able to robot navigate to the goal pose.
Example of action client snippet:
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
# Create a MoveBase Client
client = actionlib.SimpleActionClient('move_base', MoveBaseAction)
client.wait_for_server()
# Create a Goal in map and send it
goal = MoveBaseGoal()
goal.target_pose.header.frame_id = "map"
goal.target_pose.header.stamp = rospy.Time.now()
goal.target_pose.pose.position.x = X
goal.target_pose.pose.position.y = Y
goal.target_pose.pose.orientation.w = 1.0
self.action_goal = goal
self.client.send_goal(goal)
You can read more about accessing saved MHI maps and using them in the this Readme.
Let us know if you have more doubts.