frankaemika/franka_ros

Panda with mobile robot gazebo crash

Closed this issue · 15 comments

Hi Everyone,

because I couldn't find any solution, I decided to write about my issue.

On ROS Noetic I try to put Panda robot on the Clearpath dingo robot.
I did it with xacro file

<?xml version="1.0"?>
<robot name="mobile_platform" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:include filename="$(find dingo_description)/urdf/dingo.urdf.xacro" ns="platform"/>
  <xacro:include filename="$(find franka_description)/robots/panda/panda.urdf.xacro" ns="arm"/>
  
  <xacro:include filename="$(find mobile-platform)/urdf/_d435.urdf.xacro"/>
  <xacro:sensor_d435 parent="base_link" topics_ns="camera_front">
    <origin xyz="0.35  0 0.1" rpy="0 -0.13 0"/>
  </xacro:sensor_d435>

  <joint name="panda_base_joint" type="fixed">
    <parent link="base_link"/>
    <child link="panda_link0"/>
    <origin xyz="0 0 0.1"/>
  </joint>
</robot>

After running roslaunch urdf_tutorial display.launch model:=mobile-platform-with-arm.urdf.xacro in rviz everything looks fine, but when I try to launch everything in gazebo with this launch

<launch>
    <!-- node for platform -->
    <arg name="config" default="$(optenv DINGO_CONFIG front_laser)" />
    <arg name="use_sim_time" default="true" />
    <arg name="gui" default="true" />
    <arg name="headless" default="false" />
    <arg name="world_name" default="office_small.world" />
    <arg name="arm_id" default="panda"/>
    <arg name="arm_namespace" default="panda"/>
    <!-- <arg name="x"         default="0"/>
    <arg name="y"         default="0"/>
    <arg name="z"         default="0.1"/>
    <arg name="yaw"       default="0"/> -->
    
    <!-- <rosparam command="load" file="$(find dingo_gazebo)/config/control_omni.yaml" /> -->
    
    <param name="robot_description"
      command="$(find dingo_description)/scripts/env_run
      $(find dingo_description)/urdf/configs/$(arg config)
      $(find xacro)/xacro $(find mobile-platform)/urdf/mobile-platform-with-arm.urdf.xacro" />
  
    <rosparam file="$(find mobile-platform)/config/gains.yaml" subst_value="true"/>
    <rosparam file="$(find franka_gazebo)/config/sim_controllers.yaml" subst_value="true" ns="arm"/>
    <rosparam command="load" file="$(find dingo_gazebo)/config/gains_omni.yaml" ns="platform"/>
  
    <param name="m_ee" value="0.76" />  

    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" /> 
    <node name="joint_state_publisher" type="joint_state_publisher" pkg="joint_state_publisher">
      <rosparam param="source_list">[franka_state_controller/joint_states, franka_gripper/joint_states] </rosparam>
      <param name="rate" value="30"/>
    </node>  

   <!-- <remap from="/dingo_velocity_controller/cmd_vel" to="/cmd_vel"/> -->

    <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
          args="-urdf -model mobile_platform -param robot_description" />
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="debug" value="0" />
        <arg name="gui" value="$(arg gui)" />
        <arg name="use_sim_time" value="$(arg use_sim_time)" />
        <arg name="headless" value="$(arg headless)" />
        <arg name="world_name" value="$(arg world_name)" />
        <arg name="paused" value="true"/>
    </include>
  </launch>

Gazebo is launching, robot is spawned and then gzserver crashes.
image
image

franka_hw_sim checks joints to register, but because of the dingo robot, the amount of joints is bigger than 7. I tried to change namespaces for ros_control plugins in dingo and panda urdf's but I am clueless how to solve it.

I hope I asked in proper place. Separately, both robots are working, but launching them in one simulation to create mobile panda exceed my skills.

Command line after launching with errors and warnings I put in file below.
command.txt

It would be awesome if someone could give me a hint to solve this.

Hi @kosmonauta144,

interesting problem. This is definitely the right place for the issue. Out of the blue I don't have an immediate solution. But what seems a bit strange to me is that the arm works independently for you. Actually it shouldn't because for simulating our robot in gazebo you need to provide the gazebo:=true argument to the URDF, which I cannot find in your example. Can you please try the following:

Instead of including the panda.urdf.xacro (which instantiates the robot directly) only include the panda.xacro file and than instantiate the robot manually with the correct args, i.e.:

<robot name="mobile_platform" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:include filename="$(find dingo_description)/urdf/dingo.urdf.xacro" ns="platform"/>
  <xacro:include filename="$(find franka_description)/robots/panda/panda.xacro"/> <!-- only include the macro -->

  <!-- instantiate the arm -->
  <xacro:franka_robot arm_id="arm" gazebo:="true" />

  <!-- ... rest of your urdf .. -->  

</robot>

The gazebo does a couple of things, but most notably for you adds the right transmission interfaces for FrankaHWSim (refer here for details)

There is one caveat to this, though. With providing gazebo:=true you attach a world root link to the panda_link0 which fixes the robot in place. Probably you want to remove that in favor of mounting on your mobile platform:

<!-- Gazebo requires a joint to a link called "world" for statically mounted robots -->
<link name="world" />
<joint name="world_joint" type="fixed">
<origin xyz="$(arg xyz)" rpy="$(arg rpy)" />
<parent link="world" />
<child link="$(arg arm_id)_link0" />
</joint>

Another thing is probably this:

assert(this->eji_.getNames().size() >= 7);
assert(this->pji_.getNames().size() == 7);
assert(this->vji_.getNames().size() == 7);
assert(this->jsi_.getNames().size() >= 7);
assert(this->fsi_.getNames().size() == 1);
assert(this->fmi_.getNames().size() == 1);

Since the FrankaHWSim plugin is loaded for the entire robot (arm + base) some of these assertions will obviously fail, like in your error log, that there are more than 7 velocity interfaces. Possible quick fix: replace all == with >= and recompile ;)

Let me know if any of that works for you. Probably some of these changes will have to go into franka_gazebo as well

Thanks for reporting

Hi @gollth ,

thank you for your suggestions,

I cheated a little bit with this gazebo:=true parameter and I locally removed the part with adding world link and needed joint and I do it outside the panda.urdf.xacro in additional urdf file

<?xml version="1.0"?>
<robot name="only_panda" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:include filename="$(find franka_description)/robots/panda/panda.urdf.xacro"/>
  <xacro:include filename="$(find mobile-platform)/urdf/_d435.urdf.xacro"/>
  <!-- <xacro:include filename="$(find mobile-platform)/urdf/_d435.gazebo.xacro"/> -->
  <link name="world" />
  <joint name="world_joint" type="fixed">
    <origin xyz="0 0 0" rpy="0 0 0" />
    <parent link="world" />
    <child  link="panda_link0" />
  </joint>
 </robot>

that's why panda is working alone. When I try to launch mobile platform with arm attached, I use xacro file with link connecting base_link and panda_link0

Also, I tried your idea with changing "==" to ">=" and recompiling and the error disappeared, but I am still getting errors and gazebo crashed with information

Segmentation fault (core dumped)
[gazebo-5] process has died [pid 158872, exit code 139, cmd /opt/ros/noetic/lib/gazebo_ros/gzserver -u -e ode office_small.world __name:=gazebo __log:=/home/marabir/.ros/log/54c1645c-984c-11ed-8c81-475534a10825/gazebo-5.log].

during tests, I noticed an error which occurs everytime I try to launch both mobile robot and arm

Transmission panda_franka_state has more than one joint. Currently the default robot hardware simulation  interface only supports one.

and I am wondering if it can be a hw_transmission problem and I found this issue https://github.com/ros-simulation/gazebo_ros_pkgs/issues/297 in gazebo_ros_control and I am wondering if i need hw_transmission interface if I only use panda in simulation?

Tommorow I will try to isolate both control plugins with this https://github.com/ipa320/cob_gazebo_plugins/tree/indigo_dev/cob_gazebo_ros_control and I will let you know about the result.

also, if you have time and you would like to try to check the error by yourself, we put the code in additional repo with clones of needed repos for working and they are available here with instruction how to launch everything
https://github.com/Edekheh/human-assistant/tree/develop

gollth commented

Hey @kosmonauta144,

I finally got some time to investigate your issue.

It seems your problem is actually a bug inside FrankaHWSim. Here we blindly assumed, that all joints with a transmission interface belong to the robot. This obviously breaks apart in your case, where you have URDF with joints from different "subrobots" so to say.

I created a PR which could solve your problem, can you please try to pull that branch and see if it works for you?

I cheated a little bit with this gazebo:=true parameter and I locally removed the part with adding world link

Aha I see ;)
Note that in the same branch I added a parent (and base_xyz and base_rpy) xacro argument, so you don't have to manually adjust the URDF anymore. Now something like this should work for you:

<robot name="mobile_platform_with_arm">
  <xacro:include filename="$(find dingo_description)/urdf/dingo.urdf.xacro" ns="platform"/>
  <xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro" />
  
  <!-- instantiate your platform here. Assuming it has a link called `base_link` -->
  
  <!-- Attach `fr3_link0` to `base_link`, 25cm above it -->
   <xacro:franka_robot
         robot="fr3"
         parent="base_link"
         base_xyz="0 0 0.25">
  </xacro:franka_robot>
</robot>

Would be great if you can also test that out and give us feedback.

Hope this helps

Hi @gollth

thank you for your reply, I will check this PR this weekend and let you know if it solve the issue.

gollth commented

Any news on this @kosmonauta144 ?

Hi,
sorry for long delay, ending of the academic term can be quite crazy

I tried to use new package but I am failing to check the urdf with

roslaunch urdf_tutorial display.launch model:=mobile-platform-with-arm.urdf.xacro

and I get this error

marabir@marabir-legion:~/catkin_ws/src/human-assistant/src/mobile-platform/urdf$ roslaunch urdf_tutorial display.launch model:=mobile-platform-with-arm.urdf.xacro
... logging to /home/marabir/.ros/log/98dc70b2-b48c-11ed-b4c7-2ffaef6db3b5/roslaunch-marabir-legion-22843.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

Invalid parameter "robot"
when instantiating macro: franka_robot (/home/marabir/catkin_ws/src/human-assistant/src/franka_ros/franka_description/robots/common/franka_robot.xacro)
in file: mobile-platform-with-arm.urdf.xacro
RLException: Invalid <param> tag: Cannot load command parameter [robot_description]: command [['/opt/ros/noetic/lib/xacro/xacro', 'mobile-platform-with-arm.urdf.xacro']] returned with code [2]. 

Param xml is <param name="robot_description" command="$(find xacro)/xacro $(arg model)"/>
The traceback for the exception was written to the log file

as an urdf file I used this short file

<?xml version="1.0"?>
<robot name="mobile_platform_with_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:include filename="$(find dingo_description)/urdf/dingo.urdf.xacro" ns="platform"/>
  <xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro" />
  
  <!-- instantiate your platform here. Assuming it has a link called `base_link` -->
  <!-- Attach `fr3_link0` to `base_link`, 25cm above it -->
   <xacro:franka_robot
         robot="fr3"
         parent="base_link"
         base_xyz="0 0 0.25">
  </xacro:franka_robot>
</robot>

initialization of the dingo robot is included in dingo xacro file. I am still checking if I haven't messed anything up

gollth commented

No worries,

sorry there were some more refactorings happening at the time of my last comment. I fixed also some tests. Could you try to reset your branch to the latest commit using:

cd franka_ros
git fetch
git reset --hard origin/github-\#313

Also some arguments in the URDF were renamed, so can you try to adjust your URDF like so?

<?xml version="1.0"?>
<robot name="mobile_platform_with_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:include filename="$(find dingo_description)/urdf/dingo.urdf.xacro" ns="platform"/>
  <xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro" />
  
  <!-- instantiate your platform here. Assuming it has a link called `base_link` -->
  <!-- Attach `fr3_link0` to `base_link`, 25cm above it -->
  <xacro:franka_robot arm_id="fr3"
                      joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')}"
                      hand="true"
                      gazebo="true"
                      parent="base_link"
                      xyz="0 0 0.25">
  </xacro:franka_robot>
</robot>

Let me know if that helps

I got the proper version, run everything and urdf_tutorial display gives proper result, but gazebo is still fighting.

[ INFO] [1678133742.406559805]: Loading gazebo_ros_control plugin
[ INFO] [1678133742.406623804]: Starting gazebo_ros_control plugin in namespace: /
[ INFO] [1678133742.562985132]: Using physics type ode
[ WARN] [1678133742.563853328]: Joint 'front_left_wheel' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564033812]: Joint 'front_right_wheel' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564056008]: Joint 'rear_left_wheel' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564069330]: Joint 'rear_right_wheel' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564081069]: Joint 'fr3_joint1' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564102746]: Joint 'fr3_joint2' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564125453]: Joint 'fr3_joint3' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564141995]: Joint 'fr3_joint4' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564168735]: Joint 'fr3_joint5' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564195780]: Joint 'fr3_joint6' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564226673]: Joint 'fr3_joint7' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564241729]: Joint 'fr3_joint1' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564260306]: Joint 'fr3_joint2' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564297537]: Joint 'fr3_joint3' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564332265]: Joint 'fr3_joint4' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564367205]: Joint 'fr3_joint5' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564401834]: Joint 'fr3_joint6' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564437562]: Joint 'fr3_joint7' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564472193]: Joint 'fr3_joint1' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564507307]: Joint 'fr3_joint2' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564541851]: Joint 'fr3_joint3' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564576220]: Joint 'fr3_joint4' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564610424]: Joint 'fr3_joint5' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564644653]: Joint 'fr3_joint6' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564679047]: Joint 'fr3_joint7' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564716061]: Joint 'fr3_finger_joint1' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1678133742.564751771]: Joint 'fr3_finger_joint2' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
gzserver: /home/marabir/catkin_ws/src/human-assistant/src/franka_ros/franka_gazebo/src/franka_hw_sim.cpp:228:
 virtual bool franka_gazebo::FrankaHWSim::initSim(const string&, ros::NodeHandle, gazebo::physics::ModelPtr,
 const urdf::Model*, std::vector<transmission_interface::TransmissionInfo>): 
Assertion `this->eji_.getNames().size() >= 7' failed.
[spawn_urdf-4] process has finished cleanly
log file: /home/marabir/.ros/log/a4f1bdb8-bc5b-11ed-9751-6b7bdbfb024f/spawn_urdf-4*.log
Aborted (core dumped)
[gazebo-5] process has died [pid 65304, exit code 134, cmd /opt/ros/noetic/lib/gazebo_ros/gzserver -u -e ode office_small.world __name:=gazebo __log:=/home/marabir/.ros/log/a4f1bdb8-bc5b-11ed-9751-6b7bdbfb024f/gazebo-5.log].

Gazebo still dies with no response and the same exit code. Also the gzserver error from franka_hw_sim has again occurred :/

gollth commented

This looks like the arm_id of the robot is not properly set. Can you confirm that

$ rosparam get arm_id
fr3

?

If not are you including franka_hw_sim.yaml in you launch tree somewhere (for example like here)

If that doesn't help can you please send me your launch file contents?

Hi,

I was trying to check the arm_id value, but I got the message "Parameter [/arm_id] is not set. I am including my launch file, but I don't know where I included wrong file franka_hw_sim.yaml :/ . When I commented arm_id parameter at the beginning of the launch file, I got the exception that arm_id arg has to be set and I dont understand why if it is included in xacro file which you have sent and it hasn't been called anywhere in the launch file which I use and included below
launch_file.txt

gollth commented

I think you are missing the parameters from franka_hw_sim.yaml. Note how this sets this arm_id properly based on any given launch file argument:

Therefore probably two things are missing:

  1. Include franka_hw_sim.yaml in your launch file
  2. Add an <arg /> with the name arm_id in you launch file, e.g. with a default

That is, can you try to add the following lines (A & B) to you launchfile:

<launch>
  <arg name="arm_id" default="fr3" />   <!-- A -->
  
  <arg use_sim_time default="true" />
  <!-- ... -->

  <rosparam file="$(find franka_gazebo)/config/franka_hw_sim.yaml" subst_value="true" />  <!-- B -->
  <rosparam file="$(find franka_gazebo)/config/sim_controllers.yaml" subst_value="true" ns="arm"/>

  <!-- ... -->

</launch>

Thanks for so quick reply,

I add these lines and launch file, but I got an error "Tried to advertise a service that is already advertised in this node (shown below on the screenshot). Gazebo launched without errors in pause, but when I tried to play the simulation it crashed with segmentation fault (core dumped) and gazebo-4 process has died :/
Screenshot from 2023-03-29 11-05-27

while searching for the solution I found this link https://robotics.stackexchange.com/questions/21673/tried-to-advertise-a-service-that-is-already-advertised-in-this-node-leo-contr but I am not sure if dividing controllers with different namespaces could help.

gollth commented

Again this is hard to debug without knowing the exacts of your launch + URDF files. Let's try this way. The following example should work. Can you save both of these files as

  • /tmp/test.launch and
  • /tmp/test.urdf.launch

and start them by running roslaunch /tmp/test.launch.

It's not pretty but it combines a box with a wheel with a FX3 robot. If this works for you please back-trace the difference to your setup.

<!-- test.launch -->
<?xml version="1.0"?>
<launch>

  <arg name="arm_id"      default="fr3" doc="Name of the robot to spawn" />
  <arg name="headless"    default="false" doc="Should the gazebo GUI be launched?" />
  <arg name="paused"      default="false" doc="Should the simulation directly be stopped at 0s?" />

  <arg name="initial_joint_positions"
       doc="Initial joint configuration of the panda. Specify as a list of name/value pairs in form of '-J [name-of-joint] [value-in-rad]'. Default is a 90 degree bend in the elbow"
       default="-J $(arg arm_id)_joint1 0
                -J $(arg arm_id)_joint2 -0.785398163
                -J $(arg arm_id)_joint3 0
                -J $(arg arm_id)_joint4 -2.35619449
                -J $(arg arm_id)_joint5 0
                -J $(arg arm_id)_joint6 1.57079632679
                -J $(arg arm_id)_joint7 0.785398163397
                -J $(arg arm_id)_finger_joint1 0.001
                -J $(arg arm_id)_finger_joint2 0.001"
       />

  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="worlds/empty.world"/>
    <!-- Always start in paused mode, and only unpause when spawning the model -->
    <arg name="paused" value="true"/>
    <arg name="gui" value="$(eval not arg('headless'))"/>
    <arg name="use_sim_time" value="true"/>
  </include>

  <param name="robot_description"
         command="xacro /tmp/test.urdf.xacro">
  </param>

  <rosparam file="$(find franka_gazebo)/config/franka_hw_sim.yaml" subst_value="true" />
  <rosparam file="$(find franka_gazebo)/config/sim_controllers.yaml" subst_value="true" />

  <arg name="unpause" value="$(eval '' if arg('paused') else '-unpause')" />
  <node name="$(arg arm_id)_model_spawner"
        pkg="gazebo_ros"
        type="spawn_model"
        args="-param robot_description -urdf -model $(arg arm_id) $(arg unpause) -z 0.0"/>

  <node pkg="controller_manager"
        type="spawner"
        name="$(arg arm_id)_controller_spawner"
        respawn="false" output="screen"
        args="--wait-for initialized franka_state_controller cartesian_impedance_example_controller" />

  <node pkg="controller_manager"
        type="spawner"
        name="$(arg arm_id)_gripper_spawner"
        args="franka_gripper"
        respawn="false"
  />

</launch>
<!-- test.urdf.xacro -->
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fr3">
  <xacro:arg name="arm_id" default="fr3" />
  <xacro:arg name="hand" default="true" />
  <xacro:arg name="gazebo" default="true" />

  <xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro"/>
  <xacro:include filename="$(find franka_description)/robots/common/utils.xacro" />

  <link name="base_link">
    <visual>
      <origin xyz="0 0 0.1" />
      <geometry> <box size="1 1 0.1" /> </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0.1" />
      <geometry> <box size="1 1 0.1" /> </geometry>
    </collision>
  </link>

  <link name="wheel_l">
    <visual>
      <geometry> <cylinder length="0.05" radius="0.1" /> </geometry>
    </visual>

    <collision>
      <geometry> <cylinder length="0.05" radius="0.1" /> </geometry>
    </collision>
    <xacro:inertia-cylinder mass="1" radius="0.1" h="0.05" />
  </link>

  <joint name="wheel_l_joint" type="revolute">
    <origin xyz="0 0.5 0.2" />
    <axis xyz="0 1 0" />
    <parent link="base_link" />
    <child  link="wheel_l" />
    <limit lower="-3.14" upper="3.14" effort="100" velocity="100" />
  </joint>

  <xacro:franka_robot arm_id="fr3"
                      joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')}"
                      hand="true"
                      gazebo="true"
                      parent="base_link"
                      xyz="0 0 0.25">
  </xacro:franka_robot>

  <xacro:gazebo-joint joint="wheel_l_joint" transmission="hardware_interface/VelocityJointInterface" />

</robot>
gollth commented

Since I didn't hear back from you @kosmonauta144, I assume you were able to solve your issue. I will merge #321 then. Feel free to reopen the ticket if the problem persists

Hello,

I have a similar issue with a double panda, I'm just trying to launch the automatically created demo_gazebo.launch but I get this error:

 WARN] [1696667027.083806450]: Joint 'panda_1_joint1' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1696667027.083930650]: Joint 'panda_1_joint2' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim
[ WARN] [1696667027.083946060]: Joint 'panda_1_joint3' contains a 'transmission_interface/SimpleTransmission' transmission, but it's not part of the Franka robot. Ignoring this joint in FrankaHWSim

my demo_gazebo:

<?xml version="1.0"?>
<launch>

<arg name="arm_id" default="panda" />
  <!-- MoveIt options -->
  <arg name="pipeline" default="ompl" doc="Planning pipeline to use with MoveIt"/>

  <!-- Gazebo options -->
  <arg name="gazebo_gui" default="true" doc="Start Gazebo GUI"/>
  <arg name="paused" default="false" doc="Start Gazebo paused"/>
  <arg name="world_name" default="worlds/empty.world" doc="Gazebo world file"/>
  <arg name="world_pose" default="-x 0 -y 0 -z 0 -R 0 -P 0 -Y 0" doc="Pose to spawn the robot at"/>
  
    <rosparam file="$(find franka_gazebo)/config/franka_hw_sim.yaml" subst_value="true" />  <!-- B -->
  <rosparam file="$(find franka_gazebo)/config/sim_controllers.yaml" subst_value="true" />

  <!-- Launch Gazebo and spawn the robot -->
  <include file="$(dirname)/gazebo.launch" pass_all_args="true"/>

  <!-- Launch MoveIt -->
  <include file="$(dirname)/demo.launch" pass_all_args="true">
    <!-- robot_description is loaded by gazebo.launch, to enable Gazebo features -->
    <arg name="load_robot_description" value="false" />
    <arg name="moveit_controller_manager" value="ros_control" />
  </include>
</launch>

and my dual_panda.xacro:

<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
  <xacro:arg name="arm_id_1" default="panda_1" />
  <xacro:arg name="arm_id_2" default="panda_2" />

  <xacro:include filename="$(find franka_description)/robots/common/franka_arm.xacro"/>
  <xacro:include filename="$(find franka_description)/robots/common/franka_hand.xacro"/>

  <!-- box shaped table as base for the 2 Pandas -->
  <link name="base">
  </link>

  <!-- right arm with gripper -->
  <xacro:franka_arm arm_id="$(arg arm_id_1)" connected_to="base"  xyz="0 -0.5 0" safety_distance="0.03" joint_limits="${xacro.load_yaml('$(find franka_description)/robots/panda/joint_limits.yaml')}"/>
  <xacro:franka_hand arm_id="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" safety_distance="0.03"/>

  <!-- left arm with gripper -->
  <xacro:franka_arm arm_id="$(arg arm_id_2)" connected_to="base"  xyz="0 0.5 0" safety_distance="0.03" joint_limits="${xacro.load_yaml('$(find franka_description)/robots/panda/joint_limits.yaml')}"/>
  <xacro:franka_hand arm_id="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8" safety_distance="0.03"/>

</robot>

I tried what you have told above but now way, I cant make it work...