gazebo_ros2_control
gazebo_ros2_control copied to clipboard
Cannot changes namespaces or remap topics in controllers created by plugin
I tried adding <remappings>
and <namespace>
arguments inside the <urdf>
/<sdf>
. It can change the namespace of the gazebo node created through Get(sdf)
, but not the controllers created. For instance, for JointStateController
, the publishing topic can only be /joint_states
not /<namespace>/joint_states
.
Other methods to change namespaces also doesn't work since the controller interface (reference) doesn't accept a namespace argument when instantiating a lifecycle node for the controller. This won't be a problem if we have access to ros2 launch
or ros2 run
, but doesn't work with gazebo.
This could be an enhancement for anybody wants to have two instances of gazebo_ros2_control under different namespaces like me. But there is probably not much I can do with the current controller interface.
This patch allows to use namespaces:
diff --git a/gazebo_ros2_control_demos/launch/cart_example_position.launch.py b/gazebo_ros2_control_demos/launch/cart_example_position.launch.py
index b677830..f5f865a 100644
--- a/gazebo_ros2_control_demos/launch/cart_example_position.launch.py
+++ b/gazebo_ros2_control_demos/launch/cart_example_position.launch.py
@@ -46,12 +46,13 @@ def generate_launch_description():
node_robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
+ namespace='/robot1',
output='screen',
parameters=[params]
)
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
- arguments=['-topic', 'robot_description',
+ arguments=['-topic', '/robot1/robot_description',
'-entity', 'cartpole'],
output='screen')
diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf
index 2f0d8f8..923c687 100644
--- a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf
+++ b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf
@@ -60,8 +60,12 @@
</transmission>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
+ <ros>
+ <namespace>/robot1</namespace>
+ </ros>
<robot_sim_type>gazebo_ros2_control/DefaultRobotHWSim</robot_sim_type>
<parameters>$(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml</parameters>
+ <robot_param_node>/robot1/robot_state_publisher</robot_param_node>
</plugin>
</gazebo>
</robot>
Anyhow the topic /<namespace>/joint_states
it's not working. I'm looking into it
The issue is here. The lifecycle node who manage the topic is not using the right namespace:
lifecycle_node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>(controller_name);
Created issue https://github.com/ros-controls/ros2_control/issues/213
Hi, @ahcorde
Has the above problem resolved? I want to designate a namespace for spawning multiple robots in Gazebo. The patch was performed according to the above method, but the namespaces such as joint_state_controller and position_controller have not changed. Can I remap a topic or node to the namespace?
@kong2983 , it looks like the upstream issue is still open: https://github.com/ros-controls/ros2_control/issues/213
Hi all... and it is still open.
We are starting our migration to foxy
this year, and we need namespaces
in a multi-robot scenario as well.
We have detected three things so far, that we have worked in our forks to make it work as (we) expect (not sure it is every usecase around):
- The
gazebo_ros2_control
plugin remaps everything into the namespace in which a model is spawned. We saw that this affects any other gazebo ros plugin in a second model being spawned, resulting in name duplications all over, not only ros-controls wise. We commented the "__ns:=" remap flag that goes into arguments that goes into global context. We also passed the namespace to the controller manager constructor. This is the commit
At this point, the rest of the plugins works well, but we face the title of the issue: all controllers are loaded in the "/" namespace no matter what, again, duplicating node names and topics (those of the controllers only) when two instances of the same gazebo model are spawned in different namespaces. To fix this issue, we did what was suggested here.
-
We changed the
controller_interface
and how thecontroller_manager
initializes the controllers. This and this commit, respectively. -
And then, updated all controllers in
ros2_controllers
to use that newinit(...)
method. This commit.
Result: two robots of the same model, that include a lidar (gazebo_ros_ray_sensor
plugin), a ground truth for odom (gazebo_ros_p3d
plugin), and the ros control related params (gazebo_ros2_control
plugin), one in patata
and the other in marisc
namespace:
If you think these changes are worth of a PR, let us know.
Hi @carlosjoserg
This an awesome contribution! I think the steps for getting these PRs in are:
- Create PRs in
ros2_control
andros2_controllers
- Once the PRs above are merge open a PR in
gazebo_ros2_control
@bmagyar How do you see the commits mentioned before in ros2_control
and ros2_controllers
?
Hi @carlosjoserg,
Any updates on this? Did you end up making a PR? I am facing a similar issue where I cannot load two independent instances of gazebo_ros2_control with independent namespaces for each robot.
thanks in advance.
Hi @ahcorde, @carlosjoserg ,
we are also limited by this issue, as we can't simulate multi-robot systems. Any chances to get this fixed somewhere soon?
Thanks, Martino
This patch allows to use namespaces:
diff --git a/gazebo_ros2_control_demos/launch/cart_example_position.launch.py b/gazebo_ros2_control_demos/launch/cart_example_position.launch.py index b677830..f5f865a 100644 --- a/gazebo_ros2_control_demos/launch/cart_example_position.launch.py +++ b/gazebo_ros2_control_demos/launch/cart_example_position.launch.py @@ -46,12 +46,13 @@ def generate_launch_description(): node_robot_state_publisher = Node( package='robot_state_publisher', executable='robot_state_publisher', + namespace='/robot1', output='screen', parameters=[params] ) spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', - arguments=['-topic', 'robot_description', + arguments=['-topic', '/robot1/robot_description', '-entity', 'cartpole'], output='screen') diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf index 2f0d8f8..923c687 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf @@ -60,8 +60,12 @@ </transmission> <gazebo> <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control"> + <ros> + <namespace>/robot1</namespace> + </ros> <robot_sim_type>gazebo_ros2_control/DefaultRobotHWSim</robot_sim_type> <parameters>$(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml</parameters> + <robot_param_node>/robot1/robot_state_publisher</robot_param_node> </plugin> </gazebo> </robot>
Anyhow the topic
/<namespace>/joint_states
it's not working. I'm looking into it
I refer to the method you provided above, I generated four robots, thank you very much. But in the model of the robot I generated, only three robots have the cmd_vel command, and the generated gripper controller command can be loaded successfully (also appears The phenomenon of unsuccessful loading shows that the joints parameter is empty), and can be controlled through the gripper topic. The topic and the model loaded successfully can refer to the following figure. The controller library used by the robot is libgazebo_ros_planar_move.so.
Hi!
I'm having a similar problem. I'm trying to launch two different robot models, but when I insert the second model, the controller_menager crashes and doesn't recognize the controller of the second model.
I did all the procedures recommended by carlosjoserg, but I'm still unsuccessful.
Any suggestions on how this can be done?
Model 1: Omnidirecional Model 2: UR10
Hi!
I'm having a similar problem. I'm trying to launch two different robot models, but when I insert the second model, the controller_menager crashes and doesn't recognize the controller of the second model.
I did all the procedures recommended by carlosjoserg, but I'm still unsuccessful.
Any suggestions on how this can be done?
Model 1: Omnidirecional Model 2: UR10
I think you can do some procedures with @ahcorde suggestions and you must launch a robot in a origin way without namespace. But it should show my encounter problem. I wish you can do some experiments and solve this problem. I think its key is 'Anyhow the topic /nameapce/joint_states it's not working. I'm looking into it'. I also add other model (robot arm) in this situation, it can be showed in gazebo, but the controller load is error. I will try it again, if it is success, I will reply you as soon as possible.
Hi, are there any updates about this? I have applied the patch mentioned by @ahcorde . I am working on galactic and humble but either way that doesn't work (notice that I am also relying on ros2_control built from source). For the galactic branch I have the following heads:
gazebo_ros2_control: 121fc13 (origin/galactic) Merge pull request #167 from ros-controls/ahcorde/foxy_to_galactic_23_11_2022
ros2_control: 4a61389 (HEAD -> galactic, tag: 1.6.0, origin/galactic) 1.6.0
I have also looked at this and some parts of it seem to be already in the mentioned branches.
Thanks