Posted by @harshp1509:
I want to add custom task in my project but when i am running fleet adapter using this below adapter file than it is registering in rmf side:-
<?xml version='1.0' ?>
<launch>
<arg name="fleet_name" default="turtlebot3" description="Name of this fleet of turtlebot3 robots"/><!--fleet_nameをturtlebot3に修正-->
<arg name="use_sim_time" default="true" description="Use the /clock topic for time to sync with simulation"/><!--use_sim_timeをtrueに修正-->
<arg name="nav_graph_file" description="Nav graph required by fleet adapter"/>
<group>
<include file="$(find-pkg-share rmf_fleet_adapter)/fleet_adapter.launch.xml">
<!-- The name and control type of the fleet -->
<arg name="fleet_name" value="$(var fleet_name)"/>
<arg name="control_type" value="full_control"/>
<!-- The graph that this fleet should use for navigation -->
<arg name="nav_graph_file" value="$(var nav_graph_file)" />
<!-- The nominal linear and angular velocity of this fleet's vehicles -->
<arg name="linear_velocity" value="0.15"/>
<arg name="angular_velocity" value="0.75"/>
<!-- The nominal linear and angular acceleration of this fleet's vehicles -->
<arg name="linear_acceleration" value="0.1"/>
<arg name="angular_acceleration" value="0.1"/>
<!-- The radius of the circular footprint of this fleet's vehicles -->
<arg name="footprint_radius" value="0.105"/>
<!-- Other robots are not allowed within this radius -->
<arg name="vicinity_radius" value="0.15"/>
<!-- Whether to use sim time -->
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<!-- How long it can be delayed before we give up and start over -->
<arg name="delay_threshold" value="15.0"/>
<!-- Don't make the tinyRobot wait long to retry -->
<arg name="retry_wait" value="10.0"/>
<!-- Give everything time to discover -->
<arg name="discovery_timeout" value="60.0"/>
<!-- Can the robot drive backwards -->
<arg name="reversible" value="true"/>
<!-- Whether it can perform deliveries -->
<arg name="perform_deliveries" value="false"/>
<!-- Whether it can perform loop -->
<arg name="perform_loop" value="true"/>
<!-- Whether it can perform cleaning -->
<arg name="perform_cleaning" value="false"/>
<!-- What the robot should do once it finishes its tasks -->
<arg name="finishing_request" value="nothing"/>
<!-- TODO Update these values with actual specs -->
<!-- Battery parameters -->
<arg name="battery_voltage" value="11.1"/>
<arg name="battery_capacity" value="19.98"/>
<arg name="battery_charging_current" value="1.0"/>
<!-- Physical parameters -->
<arg name="mass" value="1.0"/>
<arg name="inertia" value="0.0055"/>
<arg name="friction_coefficient" value="0.22"/>
<!-- Power systems -->
<arg name="ambient_power_drain" value="20.0"/>
<arg name="tool_power_drain" value="0.0"/>
<!-- Whether to consider battery drain for task planning -->
<arg name="drain_battery" value="false"/>
<!-- Battery level at which the robot ceases to operate -->
<arg name="recharge_threshold" value="0.1"/>
</include>
</group>
</launch>
but when i am trying using config file it is not registering and below is my turtlebot3 config file . so what can be the issue with this ?
# FLEET CONFIG =================================================================
# RMF Fleet parameters
rmf_fleet:
name: "turtlebot3"
fleet_manager:
ip: "127.0.0.1"
port: 22011
user: "some_user"
password: "some_password"
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: True
task_capabilities: # Specify the types of RMF Tasks that robots in this fleet are capable of performing
loop: True
delivery: True
clean: False
finishing_request: "park" # [park, charge, nothing]
# TinyRobot CONFIG =================================================================
robots:
# Here the user is expected to append the configuration for each robot in the
# fleet.
# Configuration for tinyRobot1
ros2_tb3_0:
robot_config:
max_delay: 15.0 # allowed seconds of delay of the current itinerary before it gets interrupted and replanned
rmf_config:
robot_state_update_frequency: 10.0
start:
map_name: "turtlebot_world"
waypoint: "tb3_0_start"
orientation: 0.0 # radians
charger:
waypoint: "tb3_0_start"
Posted by @harshp1509:
In the fleet manager file,
@app.get('/open-rmf/rmf_demos_fm_status/')
in the state=self.robots.get(robot_name)
i got state.state =None to api response.
i can get the purple robot on rmf rviz but it is not able to registering. what should be the problem in this case?
Posted by @xiyuoh:
Hello! Some questions about your setup to start off:
-
Are you running this in simulation or real robots?
-
Could you share some logs from your fleet adapter terminal in a gist? It will help us better understand what’s going on.
-
Could you describe how you are setting things up? I see that you’re running our legacy fleet adapter via this launch file, but you’re also referencing the Python demos fleet manager endpoints, which is brought up from this launch file.
For context, the first one is an old approach to creating a fleet adapter and is no longer actively supported. If possible, I’d highly recommend switching to the latter which uses the EasyFullControl API. The template is provided in the fleet_adapter_template and its usage is demonstrated in rmf_demos_fleet_adapter.
Posted by @harshp1509:
I am running this in simulation.
I am integrating free fleet with open rmf. so the I am getting purple icon for turtlebot3 but it is not registering from rmf side i didn’t get yellow icon with purple one.
when i was trying using first approach using below block code i can able to register the turtlebot3.
<group>
<let name="fleet_name" value="turtlebot3"/>
<include file="$(find-pkg-share rmf_gazebo)/launch/turtlebot3_adapter.launch.xml">
<arg name="fleet_name" value="$(var fleet_name)"/>
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="nav_graph_file" value="$(find-pkg-share rmf_gazebo)/maps/world/nav_graphs/0.yaml" />
</include>
<include file="$(find-pkg-share rmf_fleet_adapter)/robot_state_aggregator.launch.xml">
<arg name="robot_prefix" value="ros1_tb3_0"/>
<arg name="fleet_name" value="$(var fleet_name)"/>
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="failover_mode" value="$(var failover_mode)"/>
</include>
</group>
But when i am trying using second approach using rmf demos fleet adapter than it is not registering. any things i have to change in turtlebot3 config file?
<group>
<include file="$(find-pkg-share rmf_demos_fleet_adapter)/launch/fleet_adapter.launch.xml">
<arg name="use_sim_time" value="$(var use_sim_time)"/>
<arg name="nav_graph_file" value="$(find-pkg-share rmf_gazebo)/maps/world/nav_graphs/0.yaml" />
<arg name="config_file" value="$(find-pkg-share rmf_gazebo)/rmf_config/turtlebot3_config.yaml"/>
</include>
</group>
below is my terminal logs:-
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [rmf_traffic_schedule-1]: process started with pid [208259]
[INFO] [rmf_traffic_blockade-2]: process started with pid [208261]
[INFO] [building_map_server-3]: process started with pid [208263]
[INFO] [schedule_visualizer_node-4]: process started with pid [208265]
[INFO] [fleetstates_visualizer_node-5]: process started with pid [208267]
[INFO] [rmf_visualization_building_systems-6]: process started with pid [208269]
[INFO] [navgraph_visualizer_node-7]: process started with pid [208271]
[INFO] [floorplan_visualizer_node-8]: process started with pid [208273]
[INFO] [obstacle_visualizer_node-9]: process started with pid [208275]
[INFO] [rviz2-10]: process started with pid [208277]
[INFO] [door_supervisor-11]: process started with pid [208279]
[INFO] [lift_supervisor-12]: process started with pid [208281]
[INFO] [rmf_task_dispatcher-13]: process started with pid [208283]
[INFO] [simple_api_server-14]: process started with pid [208285]
[INFO] [fleet_manager-15]: process started with pid [208287]
[INFO] [fleet_adapter-16]: process started with pid [208289]
[INFO] [robot_state_aggregator-17]: process started with pid [208291]
[fleetstates_visualizer_node-5] [INFO] [1730886076.097997829] [fleet_states_visualizer]: Configuring fleet_states_visualizer...
[fleetstates_visualizer_node-5] [INFO] [1730886076.098171470] [fleet_states_visualizer]: Setting parameter initial_map_name to L1
[fleetstates_visualizer_node-5] [INFO] [1730886076.098192840] [fleet_states_visualizer]: Setting parameter fleet_state_nose_scale to 0.500000
[obstacle_visualizer_node-9] [INFO] [1730886076.101425698] [rmf_obstacle_visualizer]: Beginning RMF obstacle visualizer node
[fleetstates_visualizer_node-5] [INFO] [1730886076.103992589] [fleet_states_visualizer]: Running fleet_states_visualizer...
[rmf_task_dispatcher-13] ~Initializing Dispatcher Node~
[schedule_visualizer_node-4] [INFO] [1730886076.114934152] [schedule_visualizer_node]: Setting parameter rate to 10.000000
[schedule_visualizer_node-4] [INFO] [1730886076.115027164] [schedule_visualizer_node]: Setting parameter path_width to 0.200000
[schedule_visualizer_node-4] [INFO] [1730886076.115048532] [schedule_visualizer_node]: Setting parameter initial_map_name to L1
[schedule_visualizer_node-4] [INFO] [1730886076.115064630] [schedule_visualizer_node]: Setting parameter wait_secs to 10
[schedule_visualizer_node-4] [INFO] [1730886076.115168257] [schedule_visualizer_node]: Setting parameter port to 8006
[schedule_visualizer_node-4] [INFO] [1730886076.115183162] [schedule_visualizer_node]: Setting parameter retained_history_count to 50
[navgraph_visualizer_node-7] [INFO] [1730886076.120876719] [navgraph_visualizer]: Setting parameter initial_map_name to L1
[navgraph_visualizer_node-7] [INFO] [1730886076.121003971] [navgraph_visualizer]: Setting parameter lane_width to 0.500000
[navgraph_visualizer_node-7] [INFO] [1730886076.121067095] [navgraph_visualizer]: Setting parameter lane_transparency to 0.600000
[navgraph_visualizer_node-7] [INFO] [1730886076.121093435] [navgraph_visualizer]: Setting parameter waypoint_scale to 1.300000
[navgraph_visualizer_node-7] [INFO] [1730886076.121117700] [navgraph_visualizer]: Setting parameter text_scale to 0.700000
[rmf_traffic_schedule-1] [INFO] [1730886076.122638802] [rmf_traffic_schedule_primary]: Successfully loaded logfile .rmf_schedule_node.yaml
[rmf_traffic_schedule-1] [INFO] [1730886076.125561131] [rmf_traffic_schedule_primary]: Set up heartbeat on /rmf_traffic/heartbeat with liveliness lease duration of 10000 ms and deadline of 10000 ms
[rmf_task_dispatcher-13] [INFO] [1730886076.131838068] [rmf_dispatcher_node]: Declared Time Window Param as: 2.000000 secs
[rmf_task_dispatcher-13] [INFO] [1730886076.132017350] [rmf_dispatcher_node]: Declared Terminated Tasks Max Size Param as: 100
[rmf_task_dispatcher-13] [INFO] [1730886076.132220871] [rmf_dispatcher_node]: Declared publish_active_tasks_period as: 2 secs
[rmf_task_dispatcher-13] [INFO] [1730886076.132300520] [rmf_dispatcher_node]: Use timestamp with task_id: false
[navgraph_visualizer_node-7] [INFO] [1730886076.134510131] [navgraph_visualizer]: NavGraph visualizer is running...
[rmf_traffic_blockade-2] [INFO] [1730886076.138132189] [rmf_traffic_blockade_node]: Beginning traffic blockade node
[rmf_task_dispatcher-13] [INFO] [1730886076.143315249] [rmf_dispatcher_node]: Starting task dispatcher node
[rmf_traffic_schedule-1] [INFO] [1730886076.153581420] [rmf_traffic_schedule_primary]: Beginning traffic schedule node
[rmf_traffic_schedule-1] [INFO] [1730886076.156871343] [rmf_traffic_schedule_primary]: Registered new query [1]
[schedule_visualizer_node-4] [INFO] [1730886076.162105425] [schedule_data_node]: Registering to query topic rmf_traffic/query_update_1
[schedule_visualizer_node-4] [INFO] [1730886076.183061777] [schedule_data_node]: [rmf_traffic_ros2::MirrorManager::request_update] Requesting changes for query ID [1] since beginning of recorded history
[floorplan_visualizer_node-8] [INFO] [1730886076.195443456] [floorplan_visualizer]: Configuring floorplan_visualizer...
[rmf_traffic_schedule-1] [INFO] [1730886076.196425770] [rmf_traffic_schedule_primary]: [ScheduleNode::update_mirrors] Sending remedial update starting from the beginning going to 14 for query 1
[floorplan_visualizer_node-8] [INFO] [1730886076.196765214] [floorplan_visualizer]: Setting parameter initial_map_name to L1
[floorplan_visualizer_node-8] [INFO] [1730886076.208764850] [floorplan_visualizer]: Running floorplan_visualizer...
[schedule_visualizer_node-4] [INFO] [1730886076.268404067] [schedule_visualizer_node]: Successfully connected to rmf_traffic_schedule node.
[schedule_visualizer_node-4] [INFO] [1730886076.270537873] [schedule_data_node]: Mirror handling new sync of 1 queries from schedule node [5b7ef226-6a82-44e6-a4bb-d0efa67cbc4c]
[rviz2-10] [INFO] [1730886076.488548177] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-10] [INFO] [1730886076.488615549] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[rviz2-10] [INFO] [1730886076.506569085] [rviz2]: Stereo is NOT SUPPORTED
[rmf_visualization_building_systems-6] [INFO] [1730886076.517554288] [building_systems_visualizer]: Building systems visualizer started...
[rmf_visualization_building_systems-6] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: HistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST is deprecated. Use HistoryPolicy.KEEP_LAST instead.
[rmf_visualization_building_systems-6] warnings.warn(
[rmf_visualization_building_systems-6] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: ReliabilityPolicy.RMW_QOS_POLICY_RELIABILITY_RELIABLE is deprecated. Use ReliabilityPolicy.RELIABLE instead.
[rmf_visualization_building_systems-6] warnings.warn(
[rmf_visualization_building_systems-6] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead.
[rmf_visualization_building_systems-6] warnings.warn(
[simple_api_server-14] Set Server IP to: 0.0.0.0
[simple_api_server-14] Set Server port to: 0.0.0.0:8083
[simple_api_server-14] Set RMF Websocket port to: localhost:7878
[simple_api_server-14] Starting Websocket Server
[simple_api_server-14] Starting RMF_Demos API Server: 0.0.0.0:8083, with ws://localhost:7878
[simple_api_server-14] * Serving Flask app 'rmf_demos_panel.simple_api_server'
[simple_api_server-14] * Debug mode: off
[navgraph_visualizer_node-7] [INFO] [1730886076.781717387] [navgraph_visualizer]: Publishing navgraphs on level turtlebot_world
[building_map_server-3] [INFO] [1730886076.796249304] [building_map_server]: loading map path: /home/aimavericks/ros2_rmf_ws/install/rmf_demos_maps/share/rmf_demos_maps/world/world.building.yaml
[building_map_server-3] [INFO] [1730886076.800472307] [building_map_server]: opening: /home/aimavericks/ros2_rmf_ws/install/rmf_demos_maps/share/rmf_demos_maps/world/world.png
[building_map_server-3] [INFO] [1730886076.801399336] [building_map_server]: read 5096 byte image
[building_map_server-3] [INFO] [1730886076.802154834] [building_map_server]: unable to generate GeoJSON for this map.
[building_map_server-3] [INFO] [1730886076.806030201] [building_map_server]: publishing map...
[building_map_server-3] [INFO] [1730886076.806527835] [building_map_server]: ready to serve map: "world" Ctrl+C to exit...
[rviz2-10] [INFO] [1730886076.909829951] [rviz2]: Trying to create a map of size 384 x 384 using 1 swatches
[rviz2-10] [ERROR] [1730886076.911797169] [rviz2]: Vertex Program:rviz/glsl120/indexed_8bit_image.vert Fragment Program:rviz/glsl120/indexed_8bit_image.frag GLSL link result :
[rviz2-10] active samplers with a different type refer to the same texture image unit
[fleet_adapter-16] [INFO] [1730886076.931940034] [turtlebot3_fleet_adapter]: Parameter [discovery_timeout] set to: 60.000000
[rmf_traffic_schedule-1] [INFO] [1730886077.159635677] [rmf_traffic_schedule_primary]: A new mirror is tracking query ID [1]
[schedule_visualizer_node-4] [INFO] [1730886077.159922473] [schedule_data_node]: Mirror handling new sync of 1 queries from schedule node [5b7ef226-6a82-44e6-a4bb-d0efa67cbc4c]
[fleet_adapter-16] [INFO] [1730886077.160897111] [turtlebot3_fleet_adapter]: Registering to query topic rmf_traffic/query_update_1
[fleet_adapter-16] [INFO] [1730886077.188815435] [turtlebot3_fleet_adapter]: Mirror handling new sync of 1 queries from schedule node [5b7ef226-6a82-44e6-a4bb-d0efa67cbc4c]
[fleet_adapter-16] [INFO] [1730886078.267652768] [turtlebot3_command_handle]: Finishing request: [nothing]
[fleet_adapter-16] [INFO] [1730886078.268566930] [turtlebot3_command_handle]: Fleet [turtlebot3] is configured to perform Loop tasks
[fleet_adapter-16] [INFO] [1730886078.268854849] [turtlebot3_command_handle]: Fleet [turtlebot3] is configured to perform Delivery tasks
[schedule_visualizer_node-4] [INFO] [1730886096.270492053] [schedule_data_node]: Requesting new schedule update because update timed out
[schedule_visualizer_node-4] [INFO] [1730886096.270564236] [schedule_data_node]: [rmf_traffic_ros2::MirrorManager::request_update] Requesting changes for query ID [1] since beginning of recorded history
[rmf_traffic_schedule-1] [INFO] [1730886096.279920939] [rmf_traffic_schedule_primary]: [ScheduleNode::update_mirrors] Sending remedial update starting from the beginning going to 14 for query 1
[schedule_visualizer_node-4] [INFO] [1730886116.280478191] [schedule_data_node]: Requesting new schedule update because update timed out
[schedule_visualizer_node-4] [INFO] [1730886116.280583198] [schedule_data_node]: [rmf_traffic_ros2::MirrorManager::request_update] Requesting changes for query ID [1] since version [14]
[fleet_adapter-16] [INFO] [1730886116.281586077] [turtlebot3_fleet_adapter]: Requesting new schedule update because update timed out
Posted by @xiyuoh:
I am integrating free fleet with open rmf. so the I am getting purple icon for turtlebot3 but it is not registering from rmf side i didn’t get yellow icon with purple one.
Gotcha. May I check which branch of free fleet you’re using? Things are pretty outdated on the main branch but there is a major refactor effort going on in this PR, you might want to check that out. However it is still a work in progress so do expect significant changes in the coming weeks.
But when i am trying using second approach using rmf demos fleet adapter than it is not registering. any things i have to change in turtlebot3 config file?
The rmf_demos_fleet_adapter launch file is an example of implementing the EasyFullControl fleet adapter. If you look at this navigate
API used in the demo fleet adapter, we are calling a REST endpoint to navigate the robot. The rmf_demos_fleet_adapter used to demonstrate how a fleet adapter can be integrated with different APIs, it is not a plug and play solution for you.
For immediate testing, your options are:
- Use the free_fleet PR fleet adapter, but be aware that its upstream will be under rapid development
- Implement your own EasyFullControl fleet adapter and fill in the Nav2 API inside the fleet adapter template
- We have a simplified version of a Nav2 EasyFullControl fleet adapter here, developed for the recent Gazebo Ionic release, it could be what you need.
Posted by @harshp1509:
Implement your own EasyFullControl fleet adapter and fill in the Nav2 API inside the fleet adapter template
can you guide me or can you provide me some reference to implement?
Posted by @xiyuoh:
Both rmf_demos_fleet_adapter and the Ionic demo fleet adapter are good examples of fleet adapters written using the EasyFullControl API, you can use them as reference. In fact if you only have 1 robot, you might want to try running the Ionic demo fleet adapter directly, instructions are available in the package README.