|
| 1 | +#!/usr/bin/env python |
| 2 | + |
| 3 | +""" |
| 4 | +Copyright (c) 2020, Ubiquity Robotics |
| 5 | +All rights reserved. |
| 6 | +Redistribution and use in source and binary forms, with or without |
| 7 | +modification, are permitted provided that the following conditions are met: |
| 8 | +* Redistributions of source code must retain the above copyright notice, this |
| 9 | + list of conditions and the following disclaimer. |
| 10 | +* Redistributions in binary form must reproduce the above copyright notice, |
| 11 | + this list of conditions and the following disclaimer in the documentation |
| 12 | + and/or other materials provided with the distribution. |
| 13 | +* Neither the name of display_node nor the names of its |
| 14 | + contributors may be used to endorse or promote products derived from |
| 15 | + this software without specific prior written permission. |
| 16 | +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
| 17 | +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
| 18 | +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE |
| 19 | +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE |
| 20 | +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL |
| 21 | +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR |
| 22 | +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 23 | +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, |
| 24 | +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
| 25 | +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. |
| 26 | +""" |
| 27 | + |
| 28 | +""" |
| 29 | +Example client program for sending multiple move_basic commands |
| 30 | +""" |
| 31 | + |
| 32 | +import rospy |
| 33 | +import getopt |
| 34 | +import sys |
| 35 | +import tf |
| 36 | +import actionlib |
| 37 | +from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal |
| 38 | + |
| 39 | +class Controller: |
| 40 | + """ |
| 41 | + Controller for moving the robot through predefined waypoints. |
| 42 | + Supports different patterns (line, box, octagon, figure-8). |
| 43 | + """ |
| 44 | + |
| 45 | + # Predefined waypoints (x, y, yaw, comment) |
| 46 | + waypoints = { |
| 47 | + "line": [ |
| 48 | + [0.00, 0.00, 0.000, "MOVE: Leg A"], |
| 49 | + [0.50, 0.00, 0.000, "MOVE: Leg B"] |
| 50 | + ], |
| 51 | + "box": [ |
| 52 | + [0.00, 0.00, 0.000, "MOVE: Leg A"], |
| 53 | + [0.50, 0.00, 1.570, "MOVE: Leg B"], |
| 54 | + [0.50, 0.50, 3.140, "MOVE: Leg C"], |
| 55 | + [0.00, 0.50, -1.570, "MOVE: Leg D"] |
| 56 | + ], |
| 57 | + "octagon": [ |
| 58 | + [0.40, 0.30, 0.000, "MOVE: Leg A"], |
| 59 | + [0.60, 0.10, -0.785, "MOVE: Leg B"], |
| 60 | + [0.60, -0.10, -1.571, "MOVE: Leg C"], |
| 61 | + [0.40, -0.30, -2.356, "MOVE: Leg D"], |
| 62 | + [0.20, -0.30, -3.141, "MOVE: Leg E"], |
| 63 | + [0.00, -0.10, 2.356, "MOVE: Leg F"], |
| 64 | + [0.00, 0.10, 1.571, "MOVE: Leg G"], |
| 65 | + [0.20, 0.30, 0.785, "MOVE: Leg H"] |
| 66 | + ], |
| 67 | + "figure8": [ |
| 68 | + # First Octagon |
| 69 | + [0.40, 0.30, 0.000, "MOVE: Leg A"], |
| 70 | + [0.60, 0.10, -0.785, "MOVE: Leg B"], |
| 71 | + [0.60, -0.10, -1.571, "MOVE: Leg C"], |
| 72 | + [0.40, -0.30, -2.356, "MOVE: Leg D"], |
| 73 | + [0.20, -0.30, -3.141, "MOVE: Leg E"], |
| 74 | + [0.00, -0.10, 2.356, "MOVE: Leg F"], |
| 75 | + [0.00, 0.10, 1.571, "MOVE: Leg G"], |
| 76 | + [0.20, 0.30, 0.785, "MOVE: Leg H"], |
| 77 | + # Second Octagon |
| 78 | + [-0.20, 0.30, 2.356, "MOVE: Leg I"], |
| 79 | + [-0.40, 0.30, 3.141, "MOVE: Leg J"], |
| 80 | + [-0.60, 0.10, -2.356, "MOVE: Leg K"], |
| 81 | + [-0.60, -0.10, -1.571, "MOVE: Leg L"], |
| 82 | + [-0.40, -0.30, -0.785, "MOVE: Leg M"], |
| 83 | + [-0.20, -0.30, 0.000, "MOVE: Leg N"], |
| 84 | + [0.00, -0.10, 0.785, "MOVE: Leg O"], |
| 85 | + [0.00, 0.10, 1.571, "MOVE: Leg P"] |
| 86 | + ] |
| 87 | + } |
| 88 | + |
| 89 | + def __init__(self): |
| 90 | + rospy.init_node('controller', anonymous=True) |
| 91 | + rospy.on_shutdown(self.shutdown) |
| 92 | + |
| 93 | + # Default values |
| 94 | + self.wait_at_each_vertex = True |
| 95 | + self.scale_x = 1.0 |
| 96 | + self.scale_y = 1.0 |
| 97 | + self.offset_x = 0.0 |
| 98 | + self.offset_y = 0.0 |
| 99 | + self.waypoint_name = "line" |
| 100 | + self.waypoint_list = self.waypoints[self.waypoint_name] |
| 101 | + |
| 102 | + # Parse command-line arguments |
| 103 | + self.parse_arguments() |
| 104 | + |
| 105 | + rospy.loginfo(f"Selected waypoints: {self.waypoint_name}") |
| 106 | + rospy.loginfo(f"Scale: ({self.scale_x}, {self.scale_y}), Offset: ({self.offset_x}, {self.offset_y})") |
| 107 | + rospy.loginfo(f"Total waypoints: {len(self.waypoint_list)}") |
| 108 | + |
| 109 | + def parse_arguments(self): |
| 110 | + """Parse command-line arguments to configure the waypoint navigation.""" |
| 111 | + try: |
| 112 | + opts, _ = getopt.getopt(sys.argv[1:], "hcw:s:x:y:", |
| 113 | + ["help", "continue", "waypoints=", "scale=", "offsetX=", "offsetY="]) |
| 114 | + except getopt.GetoptError: |
| 115 | + rospy.logerr("Error parsing arguments") |
| 116 | + self.print_usage() |
| 117 | + sys.exit(2) |
| 118 | + |
| 119 | + for o, a in opts: |
| 120 | + if o in ("-h", "--help"): |
| 121 | + self.print_usage() |
| 122 | + sys.exit(0) |
| 123 | + elif o in ("-c", "--continue"): |
| 124 | + self.wait_at_each_vertex = False |
| 125 | + elif o in ("-w", "--waypoints"): |
| 126 | + if a in self.waypoints: |
| 127 | + self.waypoint_name = a |
| 128 | + self.waypoint_list = self.waypoints[a] |
| 129 | + else: |
| 130 | + rospy.logerr("Invalid waypoint list name") |
| 131 | + sys.exit(2) |
| 132 | + elif o in ("-s", "--scale"): |
| 133 | + self.scale_x = self.scale_y = float(a) |
| 134 | + elif o in ("-x", "--offsetX"): |
| 135 | + self.offset_x = float(a) |
| 136 | + elif o in ("-y", "--offsetY"): |
| 137 | + self.offset_y = float(a) |
| 138 | + |
| 139 | + def publish_move_base_goal(self, x, y, yaw, comment): |
| 140 | + """Send a goal to the move_base action server.""" |
| 141 | + client = actionlib.SimpleActionClient('move_base', MoveBaseAction) |
| 142 | + client.wait_for_server() |
| 143 | + |
| 144 | + goal = MoveBaseGoal() |
| 145 | + goal.target_pose.header.frame_id = "map" |
| 146 | + goal.target_pose.header.stamp = rospy.Time.now() |
| 147 | + goal.target_pose.pose.position.x = x |
| 148 | + goal.target_pose.pose.position.y = y |
| 149 | + q = tf.transformations.quaternion_from_euler(0, 0, yaw) |
| 150 | + goal.target_pose.pose.orientation.x, goal.target_pose.pose.orientation.y, \ |
| 151 | + goal.target_pose.pose.orientation.z, goal.target_pose.pose.orientation.w = q |
| 152 | + |
| 153 | + rospy.loginfo(f"Publishing goal: {comment} | X: {x:.2f}, Y: {y:.2f}, Yaw: {yaw:.2f}") |
| 154 | + client.send_goal(goal) |
| 155 | + client.wait_for_result() |
| 156 | + |
| 157 | + if client.get_result(): |
| 158 | + rospy.loginfo(f"Waypoint reached: {comment}") |
| 159 | + else: |
| 160 | + rospy.logwarn(f"Failed to reach waypoint: {comment}") |
| 161 | + |
| 162 | + def run(self): |
| 163 | + """Main loop for waypoint navigation.""" |
| 164 | + rospy.loginfo("Starting waypoint navigation...") |
| 165 | + |
| 166 | + while not rospy.is_shutdown(): |
| 167 | + for x, y, yaw, comment in self.waypoint_list: |
| 168 | + x = (x * self.scale_x) + self.offset_x |
| 169 | + y = (y * self.scale_y) + self.offset_y |
| 170 | + |
| 171 | + self.publish_move_base_goal(x, y, yaw, comment) |
| 172 | + |
| 173 | + if self.wait_at_each_vertex: |
| 174 | + rospy.loginfo("Waiting at waypoint...") |
| 175 | + rospy.sleep(2) # Replaces raw_input for better ROS integration |
| 176 | + |
| 177 | + def shutdown(self): |
| 178 | + """Stops the robot on shutdown.""" |
| 179 | + rospy.loginfo("Shutting down waypoint controller.") |
| 180 | + |
| 181 | + @staticmethod |
| 182 | + def print_usage(): |
| 183 | + print("Usage:") |
| 184 | + print(" -h, --help Show this help message") |
| 185 | + print(" -c, --continue Continuous operation (no waiting at each vertex)") |
| 186 | + print(" -w, --waypoints Select a predefined waypoint list (line, box, octagon, figure8)") |
| 187 | + print(" -s, --scale Scale the pattern size") |
| 188 | + print(" -x, --offsetX Offset in X direction") |
| 189 | + print(" -y, --offsetY Offset in Y direction") |
| 190 | + |
| 191 | +if __name__ == "__main__": |
| 192 | + controller = Controller() |
| 193 | + controller.run() |
0 commit comments