in simulation_ws/src/aws_robomaker_simulation_common/nodes/route_manager.py [0:0]
def route_forever(self):
rate = rospy.Rate(1)
while not rospy.is_shutdown():
if self.bad_goal_counter > 10:
rospy.loginfo(
'Stopping route manager due to too many bad goals.\
Check that your occupancy map has Trinary value\
representation and is not\
visually noisy/incorrect'
)
return
else:
rospy.loginfo(
'Route mode is %s, getting next goal',
self.route_mode)
try:
if self.route_mode == 'dynamic':
# TODO: flake8 linting standard does not allow over-riding
# the built-in python method next() which is required to
# make 'self.goals' a iterator.
current_goal = self.to_move_goal(self.goals.get_next())
else:
current_goal = self.to_move_goal(next(self.goals))
except ValueError as e:
rospy.loginfo(
'No valid goal was found in the map, stopping route manager\
due to following exception,\n{0}'.format(str(e)))
return
rospy.loginfo('Sending target goal: %s', current_goal)
self.client.send_goal(current_goal)
try:
# wait 5sec for global plan to be published. If not, scan
# for a new goal..
rospy.wait_for_message(
'/move_base/DWAPlannerROS/global_plan',
Path,
timeout=5
)
if not self.client.wait_for_result():
rospy.logerr(
'Move server not ready, will try again...')
elif self.client.get_result():
rospy.loginfo('Goal done: %s', current_goal)
rate.sleep()
except rospy.exceptions.ROSException:
self.bad_goal_counter += 1
rospy.logwarn(
'No plan found for goal. Scanning for a new goal...')