ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Hi @sree,
I will do my best to answer properly all your questions.
move_base_msgs::MoveBaseGoal goal
vector and store each goal in it. You also can read them as parameter from a yaml file with the ROS parameter server. Then in the code just perform a loop for each vector goal, waiting for result and resuming in the next step when the action server returns a success. Since the move_base is based on the actionlib
paradigm you will be able to check goal status and success state in each moment, cancel goals and traverse the vector in the order you decide.Regards.
2 | No.2 Revision |
Hi @sree,
I will do my best to answer properly all your questions.
move_base_msgs::MoveBaseGoal goal
vector and store each goal in it. You also can read them as parameter from a yaml file with the ROS parameter server. Then in the code just perform a loop for each vector goal, waiting for result and resuming in the next step when the action server returns a success. Since the move_base is based on the actionlib
paradigm you will be able to check goal status and success state in each moment, cancel goals and traverse the vector in the order you decide.Regards.
EDIT:
In order to give a use case for the approach 1 I will post a chunk of code.
Disclaimer: I am not an expert on using action_lib
with python, the functioning is strictly different when comparing roscpp
and rospy
. There may be solutions that are better and more suitable in this environment, but as a simple example I think it would be good.
First of all, since you want to have a set of goals at once you can load them with a yaml file and parameter server, this can be a good points.yaml
config file to parametrize all your goals:
point_list: [
{x_pos: 1.0, y_pos: 1.0, z_pos: 0.0, w: 1.0},
{x_pos: 2.0, y_pos: 2.0, z_pos: 0.0, w: 1.0},
{x_pos: 3.0, y_pos: 3.0, z_pos: 0.0, w: 1.0},
{x_pos: 4.0, y_pos: 4.0, z_pos: 0.0, w: 1.0}
]
Take into account that you can convert this param to a simple vector instead of a dictionary.
Second, I changed the code you linked a bit so I can iterate all the goal list, and then pass every goal to the move_base
server to process:
#!/usr/bin/env python
# license removed for brevity
import rospy
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
import actionlib
from actionlib_msgs.msg import *
class GoForwardAvoid():
def __init__(self):
rospy.init_node('nav_test', anonymous=False)
#what to do if shut down (e.g. ctrl + C or failure)
rospy.on_shutdown(self.shutdown)
self._point_list = rospy.get_param('/nav_test/point_list')
self._sleep_timer = rospy.Rate(5.0)
def spin(self):
#tell the action client that we want to spin a thread by default
self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
rospy.loginfo("wait for the action server to come up")
#allow up to 5 seconds for the action server to come up
self.move_base.wait_for_server(rospy.Duration(5))
goal = MoveBaseGoal()
goal.target_pose.header.frame_id = 'base_link'
for point in self._point_list:
print("Sending Goal: (" + str(point['x_pos']) + ", " + str(point['y_pos']) + ", " + str(point['z_pos']) + ", " + str(point['w']) + ")...")
goal.target_pose.header.stamp = rospy.Time.now()
goal.target_pose.pose.position.x = point['x_pos']
goal.target_pose.pose.position.y = point['y_pos']
goal.target_pose.pose.position.z = point['z_pos']
goal.target_pose.pose.orientation.w = point['w']
#start moving
self.move_base.send_goal(goal)
#allow TurtleBot up to 60 seconds to complete task
success = self.move_base.wait_for_result(rospy.Duration(60))
if not success:
self.move_base.cancel_goal()
rospy.loginfo("The base failed to move forward 3 meters for some reason")
else:
# We made it!
state = self.move_base.get_state()
if state == GoalStatus.SUCCEEDED:
rospy.loginfo("Hooray, the base moved 3 meters forward")
def shutdown(self):
rospy.loginfo("Stop")
if __name__ == '__main__':
try:
point_mb = GoForwardAvoid()
point_mb.spin()
except rospy.ROSInterruptException:
rospy.loginfo("Exception thrown")
Then I use a launch file to load the parameters and launch the node:
<?xml version="1.0"?>
<launch>
<arg name="output" default="screen"/>
<node pkg="your_package" type="nav_test.py" name="nav_test" output="$(arg output)">
<rosparam file="$(find your_package)/config/points.yaml" command="load"/>
</node>
</launch>
Hope this can be a suitable solution for what you need.