Open TheMipmap opened 8 months ago
thanks for sharing this issue @TheMipmap .
So in order to do a multi-robot setup, it is necessary to
port id
for each robot in the java applicationIP address
for each robotOnce that's done, one can connect the robots and the controlling PC to a switch. When using this stack, launch files can then e.g. be used as follows:
ros2 launch lbr_bringup bringup.launch.py \
model:=iiwa7 # [iiwa7, iiwa14, med7, med14] \
sim:=false \
robot_name:=robot1 \
port_id:=30200 # assuming port was set to 30200
or (depending what is used)
ros2 launch lbr_fri_ros2 app.launch.py model:=iiwa7 robot_name:=robot1 port_id:=30200
The same launch file can then be re-run with a different robot_name
/ port_id
. The transforms will be pre-fixed, so, in rviz, to display the robot correctly, one has to:
Description Topic
to /robot_name/robot_description
TF prefix
in the RobotModel
to robot_name
See below:
Multi-robot setups with moveit are currently not supported in this stack, but I haven't found a good way to do this through moveit yet. One interesting way to investigate multi-robot setups with moveit is the namespace tag in xacro https://github.com/ros/xacro/issues/305.
This issue requires:
Moving forward, it might be beneficial to have an lbr_model_zoo
repository in https://github.com/lbr-stack/ for the community to share setups.
thanks for sharing this issue @TheMipmap .
So in order to do a multi-robot setup, it is necessary to
- Configure a unique
port id
for each robot in the java application- Configure a unique
IP address
for each robotOnce that's done, one can connect the robots and the controlling PC to a switch. When using this stack, launch files can then e.g. be used as follows:
ros2 launch lbr_bringup bringup.launch.py \ model:=iiwa7 # [iiwa7, iiwa14, med7, med14] \ sim:=false \ robot_name:=robot1 \ port_id:=30200 # assuming port was set to 30200
or (depending what is used)
ros2 launch lbr_fri_ros2 app.launch.py model:=iiwa7 robot_name:=robot1 port_id:=30200
The same launch file can then be re-run with a different
robot_name
/port_id
. The transforms will be pre-fixed, so, in rviz, to display the robot correctly, one has to:
- Configure the
Description Topic
to/robot_name/robot_description
- Set a
TF prefix
in theRobotModel
torobot_name
See below:
Multi-robot setups with moveit are currently not supported in this stack, but I haven't found a good way to do this through moveit yet. One interesting way to investigate multi-robot setups with moveit is the namespace tag in xacro ros/xacro#305.
Hey! How/where do we set the port number? I am looking through LBRServer.java, and cannot find anything related to the port number.
Hi @EliasTDam , in the java application, you can configure the FRI connection.
fri_configuration_ = FRIConfiguration.createRemoteConfiguration(lbr_, client_name_);
fri_configuration_.setSendPeriodMilliSec(send_period_);
fri_configuration_.setPortOnRemote(30201); // add this line and set desired port ID
ideally there would be a user interaction to set it on the fly. That would need to be added
Thanks @mhubii ! We'll continue to keep you posted on our progress.
Lack of documentation regarding the implementation of multi-robot setups.