I have a simple python program trying to publish 2 points stored in a list in sequence, but i have noticed that the first point being published has no effect. But if i publish a 2D Nav Goal
in RViz, the car starts moving, soon it reached the goal, which the program is listening to the move_base/result
, it soon publish the second point and the car starts moving as well.
So i was wondering why the car won't move when the first point is being published? I can confirm that the move
base
simple/goal
get the first PoseStamped
msg.
Here is the code:
#!/usr/bin/env python
import rospy
from visualization_msgs.msg import Marker
from geometry_msgs.msg import PoseStamped, Twist
from move_base_msgs.msg import MoveBaseActionResult, MoveBaseAction
from actionlib_msgs.msg import GoalID
import actionlib
from static_points import StaticPoints
class MultiNavServer:
def __init__(self):
self.points = StaticPoints().get_points()
self.point_index = 0
self.is_car_ready = True
self._rate = rospy.Rate(10)
self.pub_goal = rospy.Publisher('move_base_simple/goal', PoseStamped, queue_size=1)
self.pub_cancel_goal = rospy.Publisher('move_base/cancel', GoalID, queue_size=1)
self.sub_goal_result = rospy.Subscriber('move_base/result', MoveBaseActionResult, self.goal_result_callback)
self.pub_cmd_vel = rospy.Publisher('cmd_vel', Twist, queue_size=1)
def shutdown(self):
self.pub_cancel_goal.publish(GoalID())
self.pub_cmd_vel.publish(Twist())
rospy.loginfo("Shutting down multi_nav_server")
def send_goal(self):
self._rate.sleep()
goal = PoseStamped()
goal.header.frame_id = 'map'
goal.header.stamp = rospy.Time.now()
goal.pose.position.x = self.points[self.point_index].pose.position.x
goal.pose.position.y = self.points[self.point_index].pose.position.y
goal.pose.orientation.z = self.points[self.point_index].pose.orientation.z
goal.pose.orientation.w = self.points[self.point_index].pose.orientation.w
self.pub_goal.publish(goal)
# print("Publishing goal" + str(self.point_index) + ":\n" + str(goal))
self.is_car_ready = False
self.point_index += 1
def goal_result_callback(self, msg):
print("Goal reached, setting car ready...")
self.is_car_ready = True
def run(self):
rospy.on_shutdown(self.shutdown)
while not rospy.is_shutdown():
self._rate.sleep()
if self.is_car_ready and self.point_index >= len(self.points):
print("All stations reached, shutting down...")
break
if self.is_car_ready and self.point_index < len(self.points):
print("Sending point" + str(self.point_index) + "...")
self.send_goal()
self._rate.sleep()
if __name__ == '__main__':
try:
rospy.init_node('multi_nav_server_static')
multi_nav_server = MultiNavServer()
multi_nav_server.run()
except rospy.ROSInterruptException:
pass
The terminal output is:
Sending point0...
Goal reached, setting car ready...
Sending point1...
Goal reached, setting car ready...
All stations reached, shutting down...
[INFO] [1688739930.946100, 5529.329000]: Shutting down multi_nav_server
What happened above, is the program hangs at Sending point0...
, I have to manually set a 2D Nav Goal
in Rviz, soon after the goal is reached, the program send point1 and the car is moving as normal.
I was running a simulation through Gazebo, the /use_sim_time is set to true
...
What is the logic behind my bug??
Edit: I have found that the /move_base_simple/goal
and /move_base/goal
should have similar msgs being published. Like when i publish a 2D Nav Goal
in Rviz, both topics get the same target goal location. With this being said, the first location published from my program, is only being published to /move_base_simple/goal
but the second one is publishing to both topics. I think this may be the problem. How do i fix this?
thx in advance!