-
Notifications
You must be signed in to change notification settings - Fork 60
/
fleet_adapter.launch.xml
96 lines (78 loc) · 6.55 KB
/
fleet_adapter.launch.xml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
<?xml version='1.0' ?>
<launch>
<arg name="use_sim_time" default="false" description="Use the /clock topic for time to sync with simulation"/>
<arg name="control_type" description="Fleet adapter type: full_control, read_only, or read_only_blockade"/>
<arg name="fleet_name" description="Name of the fleet that this adapter will interface with"/>
<!-- Note: We give a blank default to nav_graph_file because it is not required for read_only
mode. However it is still required for full_control mode.
TODO(MXG): Investigate if there is a better way to handle conditionally required arguments. -->
<arg name="nav_graph_file" default="" description="The file path of this fleet's navigation graph"/>
<arg name="linear_velocity" description="The nominal linear velocity of the vehicles in this fleet"/>
<arg name="angular_velocity" description="The nominal angular velocity of the vehicles in this fleet"/>
<arg name="linear_acceleration" description="The nominal linear acceleration of the vehicles in this fleet"/>
<arg name="angular_acceleration" description="The nominal angular acceleration of the vehicles in this fleet"/>
<arg name="footprint_radius" description="The radius of the footprint of the vehicles in this fleet"/>
<arg name="vicinity_radius" description="The radius of the personal vicinity of the vehicles in this fleet"/>
<arg name="delay_threshold" default="10.0" description="How long to wait before replanning" />
<arg name="disable_delay_threshold" default="false" description="Disable the delay_threshold behavior" />
<arg name="retry_wait" default="10.0" description="How long a retry should wait before starting"/>
<arg name="discovery_timeout" default="10.0" description="How long to wait on discovery before giving up"/>
<arg name="reversible" default="true" description="Can the robot drive backwards"/>
<arg name="output" default="screen"/>
<arg name="perform_loop" default="false" description="Whether this fleet adapter can perform loops"/>
<arg name="perform_deliveries" default="false" description="Whether this fleet adapter can perform deliveries"/>
<arg name="perform_cleaning" default="false" description="Whether this fleet adapter can perform cleaning"/>
<arg name="finishing_request" default="nothing" description="What should happen when the robot is finished with its tasks? Options: nothing (default), park, charge"/>
<arg name="battery_voltage" description="The nominal voltage(V) of the battery in the vehicles in this fleet"/>
<arg name="battery_capacity" description="The nominal capacity(Ah) of the battery in the vehicles in this fleet"/>
<arg name="battery_charging_current" description="The nominal charging current(A) of the battery in the vehicles in this fleet"/>
<arg name="mass" description="The mass(kg) of the vehicles in this fleet"/>
<arg name="inertia" description="The inertia(kg.m^2) of the vehicles in this fleet"/>
<arg name="friction_coefficient" description="The friction coefficient of the vehicles in this fleet"/>
<arg name="ambient_power_drain" description="The power rating(W) of ambient devices (processors, sensors, etc.) of the vehicles in this fleet"/>
<arg name="tool_power_drain" description="The power rating(W) of special tools (vaccuum, cleaning systems, etc.) of the vehicles in this fleet"/>
<arg name="drain_battery" default="false" description="Whether battery drain should be considered while assigning tasks to vechiles in this fleet"/>
<arg name="recharge_threshold" default="0.2" description="The fraction of total battery capacity below which the robot must return to its charger"/>
<arg name="recharge_soc" default="1.0" description="The fraction of total battery capacity to which the robot should be charged"/>
<arg name="experimental_lift_watchdog_service" default="" description="(Experimental) The name of a service to check whether a robot can enter a lift"/>
<arg name="enable_responsive_wait" default="true" description="Should the robot wait responsively"/>
<!-- The uri is set to the TrajectoryServer uri for debugging purposes. The default port needs to be updated before merging -->
<arg name="server_uri" default="" description="The URI of the api server to trasnmit state and task infromation. If empty, information will not be transmitted"/>
<node pkg="rmf_fleet_adapter"
exec="$(var control_type)"
name="$(var fleet_name)_fleet_adapter"
output="both">
<param name="fleet_name" value="$(var fleet_name)"/>
<param name="nav_graph_file" value="$(var nav_graph_file)"/>
<param name="linear_velocity" value="$(var linear_velocity)"/>
<param name="angular_velocity" value="$(var angular_velocity)"/>
<param name="linear_acceleration" value="$(var linear_acceleration)"/>
<param name="angular_acceleration" value="$(var angular_acceleration)"/>
<param name="footprint_radius" value="$(var footprint_radius)"/>
<param name="vicinity_radius" value="$(var vicinity_radius)"/>
<param name="perform_deliveries" value="$(var perform_deliveries)"/>
<param name="perform_loop" value="$(var perform_loop)"/>
<param name="perform_cleaning" value="$(var perform_cleaning)"/>
<param name="finishing_request" value="$(var finishing_request)"/>
<param name="delay_threshold" value="$(var delay_threshold)"/>
<param name="disable_delay_threshold" value="$(var disable_delay_threshold)"/>
<param name="retry_wait" value="$(var retry_wait)"/>
<param name="discovery_timeout" value="$(var discovery_timeout)"/>
<param name="reversible" value="$(var reversible)"/>
<param name="battery_voltage" value="$(var battery_voltage)"/>
<param name="battery_capacity" value="$(var battery_capacity)"/>
<param name="battery_charging_current" value="$(var battery_charging_current)"/>
<param name="mass" value="$(var mass)"/>
<param name="inertia" value="$(var inertia)"/>
<param name="friction_coefficient" value="$(var friction_coefficient)"/>
<param name="ambient_power_drain" value="$(var ambient_power_drain)"/>
<param name="tool_power_drain" value="$(var tool_power_drain)"/>
<param name="drain_battery" value="$(var drain_battery)"/>
<param name="recharge_threshold" value="$(var recharge_threshold)"/>
<param name="recharge_soc" value="$(var recharge_soc)"/>
<param name="experimental_lift_watchdog_service" value="$(var experimental_lift_watchdog_service)"/>
<param name="enable_responsive_wait" value="$(var enable_responsive_wait)"/>
<param name="server_uri" value="$(var server_uri)"/>
<param name="use_sim_time" value="$(var use_sim_time)"/>
</node>
</launch>