Skip to content
This repository has been archived by the owner on Apr 12, 2024. It is now read-only.

Commit

Permalink
Change slam_mode_goal back to send msgs move_base via the action client.
Browse files Browse the repository at this point in the history
  • Loading branch information
zghera committed Feb 27, 2022
1 parent ab2baa6 commit fd00c09
Showing 1 changed file with 10 additions and 17 deletions.
27 changes: 10 additions & 17 deletions src/slam_mode_goal/slam_mode_goal.py
Original file line number Diff line number Diff line change
Expand Up @@ -231,12 +231,11 @@ def callback(laserscan):
from the ROS system. With each new message this function sends a new
movement goal based on potential field avoidance and obstacle collision.
"""

# Create the action client that sends messages to move base
# client = actionlib.SimpleActionClient("move_base", MoveBaseAction)
client = actionlib.SimpleActionClient("move_base", MoveBaseAction)

# Wait for initialization of the action client
# client.wait_for_server()
client.wait_for_server()

# Initialize the move base goal message to be sent
goal = MoveBaseGoal()
Expand All @@ -253,31 +252,25 @@ def callback(laserscan):
# Send the goal and sleep while the goal is followed
# The sleep prevents a "stop and go" behavior and instead
# calculates the vectors as the kart is moving
# client.send_goal(goal)
client.send_goal(goal)
time.sleep(UPDATE_RATE)

pub.publish(goal)


"""
This should be the main function running, as it receives
laserscan messages it should interrupt and perform the operations
on the vector field.
"""
def laserscan_listener():
try:
rospy.init_node("move_base_sequence", anonymous=True)

global pub
pub = rospy.Publisher('amp_goal_position', MoveBaseGoal, queue_size=10)

rospy.Subscriber("top/scan", LaserScan, callback, queue_size=1)
rospy.spin()
except rospy.ROSInterruptException:
rospy.loginfo("Navigation Complete.")
try:
rospy.init_node("move_base_sequence", anonymous=True)
rospy.Subscriber("top/scan", LaserScan, callback, queue_size=1)
rospy.spin()
except rospy.ROSInterruptException:
rospy.loginfo("Navigation Complete.")



if __name__ == "__main__":
laserscan_listener()
laserscan_listener()

0 comments on commit fd00c09

Please sign in to comment.