diff --git a/rmf_demos/config/chart_lab/deliveryRobot_config.yaml b/rmf_demos/config/chart_lab/deliveryRobot_config.yaml new file mode 100644 index 00000000..92688d89 --- /dev/null +++ b/rmf_demos/config/chart_lab/deliveryRobot_config.yaml @@ -0,0 +1,44 @@ +# FLEET CONFIG ================================================================= +# RMF Fleet parameters + +rmf_fleet: + name: "deliveryRobot" + limits: + linear: [0.7, 0.75] # velocity, acceleration + angular: [0.6, 2.0] # velocity, acceleration + profile: # Robot profile is modelled as a circle + footprint: 0.6 # radius in m + vicinity: 0.8 # radius in m + reversible: True # whether robots in this fleet can reverse + # TODO Update battery parameters with actual specs + battery_system: + voltage: 24.0 # V + capacity: 40.0 # Ahr + charging_current: 8.8 # A + mechanical_system: + mass: 70.0 # kg + moment_of_inertia: 40.0 #kgm^2 + friction_coefficient: 0.22 + ambient_system: + power: 20.0 # W + tool_system: + power: 0.0 # W + recharge_threshold: 0.10 # Battery level below which robots in this fleet will not operate + recharge_soc: 1.0 # Battery level to which robots in this fleet should be charged up to during recharging tasks + max_delay: 15.0 # allowed seconds of delay of the current itinerary before it gets interrupted and replanned + publish_fleet_state: 10.0 # Publish frequency for fleet state, ensure that it is same as robot_state_update_frequency + account_for_battery_drain: True + task_capabilities: # Specify the types of RMF Tasks that robots in this fleet are capable of performing + loop: True + delivery: True + finishing_request: "nothing" # [park, charge, nothing] + robots: + deliveryBot_1: + charger: "d_charger" + +fleet_manager: + ip: "127.0.0.1" + port: 22012 + user: "some_user" + password: "some_password" + robot_state_update_frequency: 10.0 diff --git a/rmf_demos/config/chart_lab/tinyRobot_config.yaml b/rmf_demos/config/chart_lab/tinyRobot_config.yaml new file mode 100644 index 00000000..ace7bf9d --- /dev/null +++ b/rmf_demos/config/chart_lab/tinyRobot_config.yaml @@ -0,0 +1,46 @@ +# FLEET CONFIG ================================================================= +# RMF Fleet parameters + +rmf_fleet: + name: "tinyRobot" + limits: + linear: [0.5, 0.75] # velocity, acceleration + angular: [0.6, 2.0] # velocity, acceleration + profile: # Robot profile is modelled as a circle + footprint: 0.3 # radius in m + vicinity: 0.5 # radius in m + reversible: True # whether robots in this fleet can reverse + battery_system: + voltage: 12.0 # V + capacity: 24.0 # Ahr + charging_current: 5.0 # A + mechanical_system: + mass: 20.0 # kg + moment_of_inertia: 10.0 #kgm^2 + friction_coefficient: 0.22 + ambient_system: + power: 20.0 # W + tool_system: + power: 0.0 # W + recharge_threshold: 0.10 # Battery level below which robots in this fleet will not operate + recharge_soc: 1.0 # Battery level to which robots in this fleet should be charged up to during recharging tasks + publish_fleet_state: 10.0 # Publish frequency for fleet state, ensure that it is same as robot_state_update_frequency + account_for_battery_drain: False + task_capabilities: # Specify the types of RMF Tasks that robots in this fleet are capable of performing + loop: True + delivery: True + actions: ["teleop"] + finishing_request: "nothing" # [park, charge, nothing] + responsive_wait: False # Should responsive wait be on/off for the whole fleet by default? False if not specified. + use_parking_reservations: True + reassign_task_interval: 120 # seconds, specify how often a task reassignment should be triggered in the fleet + robots: + tinyBot_1: + charger: "t_charger" + responsive_wait: False # Should responsive wait be on/off for this specific robot? Overrides the fleet-wide setting. + +fleet_manager: + ip: "127.0.0.1" + port: 22011 + user: "some_user" + password: "some_password" diff --git a/rmf_demos/launch/chart_lab.launch.xml b/rmf_demos/launch/chart_lab.launch.xml new file mode 100644 index 00000000..b1565ffa --- /dev/null +++ b/rmf_demos/launch/chart_lab.launch.xml @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rmf_demos/launch/common.launch.xml b/rmf_demos/launch/common.launch.xml index 8654553e..2f48d927 100644 --- a/rmf_demos/launch/common.launch.xml +++ b/rmf_demos/launch/common.launch.xml @@ -82,5 +82,11 @@ + + + + + + diff --git a/rmf_demos/launch/include/chart_lab/chart_lab.rviz b/rmf_demos/launch/include/chart_lab/chart_lab.rviz new file mode 100644 index 00000000..031e18f9 --- /dev/null +++ b/rmf_demos/launch/include/chart_lab/chart_lab.rviz @@ -0,0 +1,204 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 138 + Name: Displays + Property Tree Widget: + Expanded: + - /MarkerArray3/Topic1 + - /MarkerArray4/Topic1 + Splitter Ratio: 0.5 + Tree Height: 270 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rmf_visualization_rviz2_plugins/SchedulePanel + Finish: 600 + Map: L1 + Name: SchedulePanel + Topic: /rmf_visualization/parameters + - Class: rmf_visualization_rviz2_plugins/DoorPanel + Name: DoorPanel +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: false + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: false + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MarkerArray + Namespaces: + fleet_markers: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /fleet_markers + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MarkerArray + Namespaces: + participant 0: true + participant location 0: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /schedule_markers + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MarkerArray + Namespaces: + labels: true + map: true + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /map_markers + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MarkerArray + Namespaces: + coe_door: true + coe_door_text: true + hardware_door: true + hardware_door_text: true + main_door: true + main_door_text: true + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /building_systems_markers + Value: true + - Alpha: 0.7 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: true + Enabled: true + Name: Map + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /floorplan + Update Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /floorplan_updates + Use Timestamp: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Angle: 0 + Class: rviz_default_plugins/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Scale: 95.94175720214844 + Target Frame: + Value: TopDownOrtho (rviz_default_plugins) + X: 14.163299560546875 + Y: -7.102552890777588 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + DoorPanel: + collapsed: false + Height: 1726 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000033400000622fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000006e000001910000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fc0000006e000006220000062201000039fa000000020100000003fb0000001a005300630068006500640075006c006500500061006e0065006c0100000000ffffffff0000028300fffffffb000000120044006f006f007200500061006e0065006c0100000000ffffffff0000029300fffffffb000000120052004d0046002000500061006e0065006c0100000000000003340000033400ffffff000000010000015f00000765fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000006e000007650000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000006440000062200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + SchedulePanel: + collapsed: false + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 2436 + X: 4064 + Y: 116 diff --git a/rmf_demos_gz/launch/chart_lab.launch.xml b/rmf_demos_gz/launch/chart_lab.launch.xml new file mode 100644 index 00000000..9b99b0a3 --- /dev/null +++ b/rmf_demos_gz/launch/chart_lab.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/rmf_demos_maps/maps/chart_lab/chart.png b/rmf_demos_maps/maps/chart_lab/chart.png new file mode 100644 index 00000000..e729f3af Binary files /dev/null and b/rmf_demos_maps/maps/chart_lab/chart.png differ diff --git a/rmf_demos_maps/maps/chart_lab/chart_lab.building.yaml b/rmf_demos_maps/maps/chart_lab/chart_lab.building.yaml new file mode 100644 index 00000000..21eb7c65 --- /dev/null +++ b/rmf_demos_maps/maps/chart_lab/chart_lab.building.yaml @@ -0,0 +1,357 @@ +coordinate_system: reference_image +crowd_sim: + agent_groups: + - {agents_name: [deliveryBot_1, tinyBot_1], agents_number: 2, group_id: 0, profile_selector: external_agent, state_selector: external_static, x: 0, y: 0} + agent_profiles: + - {ORCA_tau: 1, ORCA_tauObst: 0.40000000000000002, class: 1, max_accel: 0, max_angle_vel: 0, max_neighbors: 10, max_speed: 0, name: external_agent, neighbor_dist: 5, obstacle_set: 1, pref_speed: 0, r: 0.25} + enable: 0 + goal_sets: [] + model_types: [] + obstacle_set: {class: 1, file_name: L1_navmesh.nav, type: nav_mesh} + states: + - {final: 1, goal_set: -1, name: external_static, navmesh_file_name: ""} + transitions: [] + update_time_step: 0.10000000000000001 +graphs: + {} +levels: + L1: + drawing: + filename: chart.png + elevation: 0 + fiducials: + - [489.91899999999998, 2123.9549999999999, ref2] + - [487.98899999999998, 1107.5340000000001, ref1] + - [2727.5909999999999, 1107.8420000000001, ref3] + - [2723.6379999999999, 2130.672, ref4] + floors: + - parameters: {ceiling_scale: [3, 1], ceiling_texture: [1, blue_linoleum], indoor: [2, 0], texture_name: [1, blue_linoleum], texture_rotation: [3, 0], texture_scale: [3, 1]} + vertices: [2, 50, 20, 31] + lanes: + - [53, 54, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [54, 55, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [55, 56, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [55, 57, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [57, 58, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [57, 59, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [59, 60, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [54, 61, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [62, 63, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [63, 64, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [64, 61, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 0], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [65, 63, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 1], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [63, 62, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 1], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [63, 64, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 1], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + - [64, 61, {bidirectional: [4, true], demo_mock_floor_name: [1, ""], demo_mock_lift_name: [1, ""], graph_idx: [2, 1], mutex: [1, ""], orientation: [1, ""], speed_limit: [3, 0]}] + layers: + {} + measurements: + - [0, 1, {distance: [3, 8.4000000000000004]}] + models: + - {dispensable: false, model_name: OpenRobotics/AirportBench, name: OpenRobotics/AirportBench, static: true, x: 1776.491, y: 1151.0119999999999, yaw: -1.5713999999999999, z: 0} + - {dispensable: false, model_name: OpenRobotics/AirportBench, name: OpenRobotics/AirportBench, static: true, x: 1912.0129999999999, y: 1151.0119999999999, yaw: 1.5708, z: 0} + - {dispensable: false, model_name: OpenRobotics/AirportBench, name: OpenRobotics/AirportBench, static: true, x: 2042.6949999999999, y: 1151.0119999999999, yaw: 1.5708, z: 0} + vertices: + - [68.242999999999995, 707.32299999999998, 0, ""] + - [68.242999999999995, 1366.1700000000001, 0, ""] + - [463.75, 1082.825, 0, ""] + - [1403.9480000000001, 1080.48, 0, ""] + - [1640.8409999999999, 1080.423, 0, ""] + - [1642.039, 1556.4190000000001, 0, ""] + - [1641.6769999999999, 1608.9659999999999, 0, ""] + - [1641.6769999999999, 1791.258, 0, ""] + - [1641.5940000000001, 1860.7190000000001, 0, ""] + - [1641, 1951.864, 0, ""] + - [1541.047, 1952.645, 0, ""] + - [1449.9200000000001, 1954.221, 0, ""] + - [1321.502, 1954.6590000000001, 0, ""] + - [1206.694, 1952.645, 0, ""] + - [1127.4469999999999, 1951.923, 0, ""] + - [1130.511, 2161.7979999999998, 0, ""] + - [1449.9200000000001, 2161.7979999999998, 0, ""] + - [1641, 2163.2530000000002, 0, ""] + - [2300.0749999999998, 1592.7750000000001, 0, ""] + - [2756.2130000000002, 1594.242, 0, ""] + - [2754.125, 2163.6039999999998, 0, ""] + - [464.77999999999997, 1355.4269999999999, 0, ""] + - [896.70699999999999, 1356.604, 0, ""] + - [896.11900000000003, 1292.463, 0, ""] + - [1269.2, 1081.942, 0, ""] + - [896.26599999999996, 1083.7080000000001, 0, ""] + - [896.11900000000003, 1145.348, 0, ""] + - [895.52999999999997, 1447.8150000000001, 0, ""] + - [896.60599999999999, 1541.5519999999999, 0, ""] + - [898.81899999999996, 1597.961, 0, ""] + - [465.24400000000003, 1595.748, 0, ""] + - [465.459, 2162.134, 0, ""] + - [976.66099999999994, 1992.154, 0, ""] + - [1041.174, 1991.4290000000001, 0, ""] + - [1040.8119999999999, 2057.7539999999999, 0, ""] + - [976.29899999999998, 2057.0300000000002, 0, ""] + - [976.16700000000003, 1333.722, 0, ""] + - [1040.7270000000001, 1333.722, 0, ""] + - [1039.702, 1397.2080000000001, 0, ""] + - [976.54200000000003, 1397.5309999999999, 0, ""] + - [1641.2929999999999, 1333.5889999999999, 0, ""] + - [1699.6120000000001, 1334.0409999999999, 0, ""] + - [1700.0640000000001, 1398.2370000000001, 0, ""] + - [1642.6489999999999, 1397.7850000000001, 0, ""] + - [1641.6099999999999, 1463.4490000000001, 0, ""] + - [1641.3510000000001, 1990.49, 0, ""] + - [1699.992, 1989.788, 0, ""] + - [1699.992, 2056.8560000000002, 0, ""] + - [1641.3510000000001, 2057.558, 0, ""] + - [2299.8099999999999, 1080.337, 0, ""] + - [2756.2730000000001, 1081.932, 0, ""] + - [2132.1689999999999, 1081.2149999999999, 0, ""] + - [2133.2869999999998, 1198.4860000000001, 0, ""] + - [2215.4180000000001, 1183.0909999999999, 0, d_charger, {is_charger: [4, true], is_holding_point: [4, true], is_parking_spot: [4, true], spawn_robot_name: [1, deliveryBot_1], spawn_robot_type: [1, Open-RMF/DeliveryRobot]}] + - [2215.4180000000001, 1291.97, 0, ""] + - [2041.701, 1291.97, 0, ""] + - [2041.701, 1202.665, 0, ""] + - [1910.8009999999999, 1291.97, 0, ""] + - [1910.8009999999999, 1194.1010000000001, 0, ""] + - [1776.231, 1291.97, 0, ""] + - [1776.231, 1189.2080000000001, 0, ""] + - [2202.1709999999998, 1727.4290000000001, 0, consultation_zone_entry] + - [2203.1979999999999, 1869.1420000000001, 0, consultation_zone_exit] + - [1983.441, 1870.1690000000001, 0, ""] + - [1983.441, 1727.4290000000001, 0, ""] + - [1777.0450000000001, 2089.8159999999998, 0, t_charger, {is_charger: [4, true], is_holding_point: [4, true], is_parking_spot: [4, true], spawn_robot_name: [1, tinyBot_1], spawn_robot_type: [1, Open-RMF/TinyRobot]}] + walls: + - [3, 4, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [5, 6, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [7, 8, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [9, 10, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [11, 12, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [13, 14, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [14, 15, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [15, 16, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [16, 11, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [16, 17, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [18, 19, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [19, 20, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [20, 17, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [2, 21, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [21, 22, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [22, 23, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [24, 25, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [25, 26, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [25, 2, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [22, 27, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [28, 29, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [29, 30, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [30, 21, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [30, 31, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [31, 15, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [32, 33, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [33, 34, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [34, 35, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [35, 32, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [36, 37, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [37, 38, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [38, 39, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [39, 36, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [40, 41, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [41, 42, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [42, 43, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [43, 40, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [4, 40, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [43, 44, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [9, 45, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [45, 46, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [46, 47, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [47, 48, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [48, 45, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [48, 17, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [49, 50, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [50, 19, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [49, 18, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [4, 51, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [51, 52, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [51, 49, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + L2: + drawing: + filename: chart.png + elevation: 8 + fiducials: + - [489.91899999999998, 2123.9549999999999, ref2] + - [487.98899999999998, 1107.5340000000001, ref1] + - [2727.5909999999999, 1107.8420000000001, ref3] + - [2723.6379999999999, 2130.672, ref4] + floors: + - parameters: {ceiling_scale: [3, 1], ceiling_texture: [1, blue_linoleum], indoor: [2, 0], texture_name: [1, blue_linoleum], texture_rotation: [3, 0], texture_scale: [3, 1]} + vertices: [2, 54, 20, 31] + layers: + {} + measurements: + - [0, 1, {distance: [3, 8.4000000000000004]}] + vertices: + - [68.242999999999995, 707.32299999999998, 0, ""] + - [68.242999999999995, 1366.1700000000001, 0, ""] + - [463.75, 1082.825, 0, ""] + - [1403.9480000000001, 1080.48, 0, ""] + - [1640.8409999999999, 1080.423, 0, ""] + - [1642.039, 1556.4190000000001, 0, ""] + - [1642.53, 1612.0409999999999, 0, ""] + - [1641.241, 1786.653, 0, ""] + - [1641.5940000000001, 1860.7190000000001, 0, ""] + - [1641, 1951.864, 0, ""] + - [1541.047, 1952.645, 0, ""] + - [1449.9200000000001, 1954.221, 0, ""] + - [1321.502, 1954.6590000000001, 0, ""] + - [1206.694, 1952.645, 0, ""] + - [1127.4469999999999, 1951.923, 0, ""] + - [1130.511, 2161.7979999999998, 0, ""] + - [1449.9200000000001, 2161.7979999999998, 0, ""] + - [1641, 2163.2530000000002, 0, ""] + - [2300.0749999999998, 1592.7750000000001, 0, ""] + - [2756.2130000000002, 1594.242, 0, ""] + - [2754.125, 2163.6039999999998, 0, ""] + - [464.77999999999997, 1355.4269999999999, 0, ""] + - [896.70699999999999, 1356.604, 0, ""] + - [896.11900000000003, 1292.463, 0, ""] + - [1269.2, 1081.942, 0, ""] + - [896.26599999999996, 1083.7080000000001, 0, ""] + - [896.11900000000003, 1145.348, 0, ""] + - [895.52999999999997, 1447.8150000000001, 0, ""] + - [896.60599999999999, 1541.5519999999999, 0, ""] + - [898.81899999999996, 1597.961, 0, ""] + - [465.24400000000003, 1595.748, 0, ""] + - [465.459, 2162.134, 0, ""] + - [976.66099999999994, 1992.154, 0, ""] + - [1041.174, 1991.4290000000001, 0, ""] + - [1040.8119999999999, 2057.7539999999999, 0, ""] + - [976.29899999999998, 2057.0300000000002, 0, ""] + - [976.16700000000003, 1333.722, 0, ""] + - [1040.7270000000001, 1333.722, 0, ""] + - [1039.702, 1397.2080000000001, 0, ""] + - [976.54200000000003, 1397.5309999999999, 0, ""] + - [1641.2929999999999, 1333.5889999999999, 0, ""] + - [1699.6120000000001, 1334.0409999999999, 0, ""] + - [1700.0640000000001, 1398.2370000000001, 0, ""] + - [1642.6489999999999, 1397.7850000000001, 0, ""] + - [1641.6099999999999, 1463.4490000000001, 0, ""] + - [2295.819, 1992.1500000000001, 0, ""] + - [2358.8339999999998, 1992.1500000000001, 0, ""] + - [2359.5940000000001, 2054.4059999999999, 0, ""] + - [2293.5419999999999, 2056.683, 0, ""] + - [1641.3510000000001, 1990.49, 0, ""] + - [1699.992, 1989.788, 0, ""] + - [1699.992, 2056.8560000000002, 0, ""] + - [1641.3510000000001, 2057.558, 0, ""] + - [2299.8099999999999, 1080.337, 0, ""] + - [2756.2730000000001, 1081.932, 0, ""] + - [2132.1689999999999, 1081.2149999999999, 0, ""] + - [2133.2869999999998, 1198.4860000000001, 0, ""] + walls: + - [3, 4, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [5, 6, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [7, 8, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [9, 10, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [11, 12, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [13, 14, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [14, 15, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [15, 16, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [16, 11, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [16, 17, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [18, 19, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [19, 20, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [20, 17, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [2, 21, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [21, 22, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [22, 23, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [24, 25, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [25, 26, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [25, 2, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [22, 27, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [28, 29, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [29, 30, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [30, 21, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [30, 31, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [31, 15, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [32, 33, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [33, 34, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [34, 35, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [35, 32, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [36, 37, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [37, 38, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [38, 39, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [39, 36, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [40, 41, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [41, 42, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [42, 43, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [43, 40, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [4, 40, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [43, 44, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [45, 46, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [46, 47, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [47, 48, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [48, 45, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [9, 49, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [49, 50, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [50, 51, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [51, 52, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [52, 49, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [52, 17, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [53, 54, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [54, 19, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [53, 18, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [4, 55, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [55, 56, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] + - [55, 53, {alpha: [3, 1], texture_height: [3, 2.5], texture_name: [1, default], texture_scale: [3, 1], texture_width: [3, 1]}] +lifts: {} +name: chart_lab +parameters: + generate_crs: [1, EPSG:3414] + suggested_offset_x: [3, 22000] + suggested_offset_y: [3, 31500] +zones: + consultation: + depth: 4 + level: L1 + transition_lanes: + - external_vertex: consultation_zone_entry + internal_vertex: wait_1 + is_entry_lane: true + is_exit_lane: false + - external_vertex: consultation_zone_entry + internal_vertex: wait_2 + is_entry_lane: true + is_exit_lane: false + - external_vertex: consultation_zone_entry + internal_vertex: wait_3 + is_entry_lane: true + is_exit_lane: false + - external_vertex: consultation_zone_exit + internal_vertex: wait_1 + is_entry_lane: false + is_exit_lane: true + - external_vertex: consultation_zone_exit + internal_vertex: wait_2 + is_entry_lane: false + is_exit_lane: true + - external_vertex: consultation_zone_exit + internal_vertex: wait_3 + is_entry_lane: false + is_exit_lane: true + vertices: + wait_1: + group: A + priority: 1 + x: 0 + y: -1.6000000000000001 + wait_2: + group: B + priority: 2 + x: 0 + y: 0 + wait_3: + group: C + priority: 3 + x: 0 + y: 1.6000000000000001 + width: 2 + x: 2387 + y: 1798 + yaw: 0 diff --git a/rmf_demos_tasks/rmf_demos_tasks/dispatch_zone.py b/rmf_demos_tasks/rmf_demos_tasks/dispatch_zone.py new file mode 100644 index 00000000..62278699 --- /dev/null +++ b/rmf_demos_tasks/rmf_demos_tasks/dispatch_zone.py @@ -0,0 +1,221 @@ +#!/usr/bin/env python3 + +# Copyright 2026 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +"""Dispatch a zone task.""" + +import argparse +import asyncio +import json +import sys +import uuid + +import rclpy +from rclpy.node import Node +from rclpy.parameter import Parameter +from rclpy.qos import QoSDurabilityPolicy as Durability +from rclpy.qos import QoSHistoryPolicy as History +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy as Reliability + +from rmf_task_msgs.msg import ApiRequest +from rmf_task_msgs.msg import ApiResponse + +############################################################################### + + +class TaskRequester(Node): + """Dispatch zone task requester.""" + + def __init__(self, argv=sys.argv): + """Initialize task requester.""" + super().__init__('task_requester') + parser = argparse.ArgumentParser() + parser.add_argument( + '-z', + '--zone', + required=True, + type=str, + help='Name of the target zone', + ) + parser.add_argument( + '-g', + '--group', + type=str, + default=None, + help='Optional group hint to filter zone waypoints', + ) + parser.add_argument( + '-o', + '--orientation', + type=float, + default=None, + help='Optional setting of robot orientation in radians at the ' + 'selected waypoint', + ) + parser.add_argument( + '-w', + '--preferred_waypoints', + nargs='+', + type=str, + default=None, + help='Optional ordered list of preferred zone waypoint names', + ) + parser.add_argument( + '-F', + '--fleet', + type=str, + help='Fleet name, should define together with robot', + ) + parser.add_argument( + '-R', + '--robot', + type=str, + help='Robot name, should define together with fleet', + ) + parser.add_argument( + '-st', + '--start_time', + help='Start time from now in secs, default: 0', + type=int, + default=0, + ) + parser.add_argument( + '-pt', + '--priority', + help='Priority value for this request (0 or 1)', + type=int, + default=None, + ) + parser.add_argument( + '--use_sim_time', + action='store_true', + help='Use sim time, default: false', + ) + parser.add_argument( + '--requester', + help='Entity that is requesting this task', + type=str, + default='rmf_demos_tasks' + ) + + self.args = parser.parse_args(argv[1:]) + self.response = asyncio.Future() + + transient_qos = QoSProfile( + history=History.KEEP_LAST, + depth=1, + reliability=Reliability.RELIABLE, + durability=Durability.TRANSIENT_LOCAL, + ) + self.pub = self.create_publisher( + ApiRequest, 'task_api_requests', transient_qos + ) + + # enable ros sim time + if self.args.use_sim_time: + self.get_logger().info('Using Sim Time') + param = Parameter('use_sim_time', Parameter.Type.BOOL, True) + self.set_parameters([param]) + + # Construct task + msg = ApiRequest() + msg.request_id = 'zone_' + str(uuid.uuid4()) + payload = {} + + if self.args.robot and self.args.fleet: + self.get_logger().info("Using 'robot_task_request'") + payload['type'] = 'robot_task_request' + payload['robot'] = self.args.robot + payload['fleet'] = self.args.fleet + else: + self.get_logger().info("Using 'dispatch_task_request'") + payload['type'] = 'dispatch_task_request' + + request = {} + + # Set task request request time and start time + now = self.get_clock().now().to_msg() + now.sec = now.sec + self.args.start_time + start_time = now.sec * 1000 + round(now.nanosec / 10**6) + request['unix_millis_request_time'] = start_time + request['unix_millis_earliest_start_time'] = start_time + if self.args.priority is not None: + request['priority'] = { + 'type': 'binary', + 'value': 1 if self.args.priority > 0 else 0, + } + + request['requester'] = self.args.requester + + # Define task request category + request['category'] = 'zone' + + if self.args.fleet: + request['fleet_name'] = self.args.fleet + + description = {'zone_name': self.args.zone} + + waypoint_preference = {} + if self.args.group is not None: + waypoint_preference['group'] = self.args.group + if self.args.orientation is not None: + waypoint_preference['orientation'] = self.args.orientation + if self.args.preferred_waypoints: + waypoint_preference['preferred_waypoints'] = \ + self.args.preferred_waypoints + + if waypoint_preference: + description['modifiers'] = { + 'waypoint_preference': waypoint_preference, + } + + request['description'] = description + payload['request'] = request + msg.json_msg = json.dumps(payload) + + def receive_response(response_msg: ApiResponse): + if response_msg.request_id == msg.request_id: + self.response.set_result(json.loads(response_msg.json_msg)) + + transient_qos.depth = 10 + self.sub = self.create_subscription( + ApiResponse, 'task_api_responses', receive_response, transient_qos + ) + + print(f'Json msg payload: \n{json.dumps(payload, indent=2)}') + self.pub.publish(msg) + + +############################################################################### + + +def main(argv=sys.argv): + """Dispatch a zone task.""" + rclpy.init(args=sys.argv) + args_without_ros = rclpy.utilities.remove_ros_args(sys.argv) + + task_requester = TaskRequester(args_without_ros) + rclpy.spin_until_future_complete( + task_requester, task_requester.response, timeout_sec=5.0 + ) + if task_requester.response.done(): + print(f'Got response: \n{task_requester.response.result()}') + else: + print('Did not get a response') + rclpy.shutdown() + + +if __name__ == '__main__': + main(sys.argv) diff --git a/rmf_demos_tasks/setup.py b/rmf_demos_tasks/setup.py index 16adf600..9018325c 100644 --- a/rmf_demos_tasks/setup.py +++ b/rmf_demos_tasks/setup.py @@ -35,6 +35,7 @@ 'dispatch_loop = rmf_demos_tasks.dispatch_loop:main', 'dispatch_action = rmf_demos_tasks.dispatch_action:main', 'dispatch_patrol = rmf_demos_tasks.dispatch_patrol:main', + 'dispatch_zone = rmf_demos_tasks.dispatch_zone:main', 'dispatch_delivery = rmf_demos_tasks.dispatch_delivery:main', 'dispatch_cart_delivery = ' 'rmf_demos_tasks.dispatch_cart_delivery:main',