首先《ros by example 1》里有个用move_base跑4个目标点的程序,先去看了下源码,发现它仅仅是把目标点发送出去,然后等待move_base60s,如果这段时间内成功完成导航任务,则继续发布下个目标点,否则退出。代码如下所示:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16
defmove(self, goal): # Send the goal pose to the MoveBaseAction server self.move_base.send_goal(goal)
# Allow 1 minute to get there finished_within_time = self.move_base.wait_for_result(rospy.Duration(60))
# If we don't get there in time, abort the goal ifnot finished_within_time: self.move_base.cancel_goal() rospy.loginfo("Timed out achieving goal") else: # We made it! state = self.move_base.get_state() if state == GoalStatus.SUCCEEDED: rospy.loginfo("Goal succeeded!")
// push the feedback out //发布一些反馈信息 move_base_msgs::MoveBaseFeedback feedback; feedback.base_position = current_position; as_->publishFeedback(feedback);
//省略。。。 }
voidMoveBase::executeCb( const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal){ // we have a goal so start the planner(通知planner线程进行路径规划) boost::unique_lock<boost::mutex> lock(planner_mutex_); planner_goal_ = goal; runPlanner_ = true; // 通知规划路径线程 planner_cond_.notify_one(); lock.unlock();
ros::NodeHandle n; while (n.ok()) { // 被抢占了(可能是发出新的goal,也可能是取消了) if (as_->isPreemptRequested()) { if (as_->isNewGoalAvailable()) { // 发布新的goal,通知planner线程工作。 planner_cond_.notify_one(); } else { // if we've been preempted explicitly we need to shut things down //强制退出 return; } } //省略。。。 } }
// Called once when the goal completes voiddoneCb(const actionlib::SimpleClientGoalState& state, const FibonacciResultConstPtr& result){ ROS_INFO("Finished in state [%s]", state.toString().c_str()); ROS_INFO("Answer: %i", result->sequence.back()); ros::shutdown(); }
// Called once when the goal becomes active voidactiveCb(){ ROS_INFO("Goal just went active"); }
// Called every time feedback is received for the goal voidfeedbackCb(const FibonacciFeedbackConstPtr& feedback){ ROS_INFO("Got Feedback of length %lu", feedback->sequence.size()); }
/** * \brief Sends a goal to the ActionServer, and also registers callbacks * * If a previous goal is already active when this is called. We simply forget * about that goal and start tracking the new goal. No cancel requests are made. * \param done_cb Callback that gets called on transitions to Done * \param active_cb Callback that gets called on transitions to Active * \param feedback_cb Callback that gets called whenever feedback for this goal * is received */ voidsendGoal(const Goal& goal, SimpleDoneCallback done_cb = SimpleDoneCallback(), SimpleActiveCallback active_cb = SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb = SimpleFeedbackCallback());
// Called once when the goal becomes active voidactiveCb(){ ROS_INFO("Goal Received"); }
// Called every time feedback is received for the goal voidfeedbackCb(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback){ // ROS_INFO("Got base_position of Feedback"); current_point.x = feedback->base_position.pose.position.x; current_point.y = feedback->base_position.pose.position.y; current_point.z = feedback->base_position.pose.position.z; }
// Need boost::bind to pass in the 'this' pointer ac.sendGoal(goal, boost::bind(&MyNode::doneCb, this, _1, _2), Client::SimpleActiveCallback(), Client::SimpleFeedbackCallback());
import rospy import actionlib from actionlib_msgs.msg import * from geometry_msgs.msg import Pose, Point, Quaternion, Twist from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal from tf.transformations import quaternion_from_euler from visualization_msgs.msg import Marker from math import radians, pi
# How big is the square we want the robot to navigate? square_size = rospy.get_param("~square_size", 1.0) # meters
# Create a list to hold the target quaternions (orientations) quaternions = list()
# First define the corner orientations as Euler angles euler_angles = (pi/2, pi, 3*pi/2, 0)
# Then convert the angles to quaternions for angle in euler_angles: q_angle = quaternion_from_euler(0, 0, angle, axes='sxyz') q = Quaternion(*q_angle) quaternions.append(q)
# Create a list to hold the waypoint poses waypoints = list()
# Append each of the four waypoints to the list. Each waypoint # is a pose consisting of a position and orientation in the map frame. waypoints.append(Pose(Point(square_size, 0.0, 0.0), quaternions[0])) waypoints.append( Pose(Point(square_size, square_size, 0.0), quaternions[1])) waypoints.append(Pose(Point(0.0, square_size, 0.0), quaternions[2])) waypoints.append(Pose(Point(0.0, 0.0, 0.0), quaternions[3]))
# Initialize the visualization markers for RViz self.init_markers()
# Set a visualization marker at each waypoint for waypoint in waypoints: p = Point() p = waypoint.position self.markers.points.append(p)
# Publisher to manually control the robot (e.g. to stop it, queue_size=5) self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=5)
# Subscribe to the move_base action server self.move_base = actionlib.SimpleActionClient( "move_base", MoveBaseAction)
rospy.loginfo("Waiting for move_base action server...")
# Wait 60 seconds for the action server to become available self.move_base.wait_for_server(rospy.Duration(60))
rospy.loginfo("Connected to move base server") rospy.loginfo("Starting navigation test")
# Initialize a counter to track waypoints i = 0
# Cycle through the four waypoints while i < 4andnot rospy.is_shutdown(): # Update the marker display self.marker_pub.publish(self.markers)
# Intialize the waypoint goal goal = MoveBaseGoal()
# Use the map frame to define goal poses goal.target_pose.header.frame_id = 'map'
# Set the time stamp to "now" goal.target_pose.header.stamp = rospy.Time.now()
# Set the goal pose to the i-th waypoint goal.target_pose.pose = waypoints[i]
# Start the robot moving toward the goal self.move(goal)
i += 1
defmove(self, goal): # Send the goal pose to the MoveBaseAction server self.move_base.send_goal(goal)
# Allow 1 minute to get there finished_within_time = self.move_base.wait_for_result( rospy.Duration(60))
# If we don't get there in time, abort the goal ifnot finished_within_time: self.move_base.cancel_goal() rospy.loginfo("Timed out achieving goal") else: # We made it! state = self.move_base.get_state() if state == GoalStatus.SUCCEEDED: rospy.loginfo("Goal succeeded!")
defshutdown(self): rospy.loginfo("Stopping the robot...") # Cancel any active goals self.move_base.cancel_goal() rospy.sleep(2) # Stop the robot self.cmd_vel_pub.publish(Twist()) rospy.sleep(1)
if __name__ == '__main__': try: MoveBaseSquare() except rospy.ROSInterruptException: rospy.loginfo("Navigation test finished.")