ros-controls / ros2_control

Generic and simple controls framework for ROS 2
https://control.ros.org
Apache License 2.0
493 stars 298 forks source link

unconfigured problem #1806

Open naorwaiss opened 2 days ago

naorwaiss commented 2 days ago

hi every one i am new here and try at the first time to configured my gazebo robot with ros2 control the problem is the controller is unconfigure and i dont find where the problem:

the urdf file

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name= "x8_robot">

<xacro:arg name="is_ignition" default="true"/>
<!--    links-->

<link name="base_link"></link>
<link name="chassis"><inertial><origin xyz="-0.00984195359459856 -0.00120925257982298 0.0505150963957082" rpy="0 0 0" /><mass value="3.83579845094888" /><inertia
    ixx="0.0108641330207659"
    ixy="-5.9823674702839E-07"
    ixz="-1.768908869104E-06"
    iyy="0.0199873663409641"
    iyz="2.49003604337839E-05"
    izz="0.0251403002191233"
/></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/base_link.STL"  /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/base_link.STL" /></geometry></collision></link>

<link name="front_left">
<inertial><origin xyz="-0.151392376561602 -0.0765244450560608 0.045198369230977" rpy="0 0 0" /><mass value="0.729027057768021" /><inertia
    ixx="0.00137456304544284"
    ixy="-0.00131718035914277"
    ixz="-7.24913767818369E-05"
    iyy="0.00280935567626702"
    iyz="-5.18206845156667E-05"
    izz="0.00402554483982116"
/></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/front_left.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/front_left.STL" /></geometry></collision></link>

<link name="front_front_left"><inertial><origin xyz="2.7273E-08 8.4788E-07 0.033785" rpy="0 0 0" /><mass value="0.62345" /><inertia
  ixx="0.0021571"
  ixy="5.7178E-10"
  ixz="1.3794E-10"
  iyy="0.0021571"
  iyz="1.1818E-08"
  izz="0.0038015"
/></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.79216 0.81961 0.93333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

<link name="front_back_left"><inertial><origin xyz="2.7284E-08 8.4791E-07 0.033785" rpy="0 0 0" /><mass value="0.62345" /><inertia
  ixx="0.0021571"
  ixy="5.7162E-10"
  ixz="1.3798E-10"
  iyy="0.0021571"
  iyz="1.1818E-08"
  izz="0.0038015"
/></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.79216 0.81961 0.93333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

 <link name="front_right"><inertial><origin xyz="-0.15140299531934 -0.076526205656618 -0.0451940468029265" rpy="0 0 0" /><mass value="0.729214138297053"/><inertia
  ixx="0.00137478227627483"
  ixy="-0.00131726895128445"
  ixz="7.25804426030585E-05"
  iyy="0.00281017626017176"
  iyz="5.18669798425697E-05"
  izz="0.00402653973335046" />
</inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/front_right.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/front_right.STL" /></geometry></collision></link>

<link name="front_back_right"><inertial><origin xyz="2.7284E-08 8.4791E-07 0.033785" rpy="0 0 0" /><mass value="0.62345" /><inertia
  ixx="0.0021571"
  ixy="5.7162E-10"
  ixz="1.3798E-10"
  iyy="0.0021571"
  iyz="1.1818E-08"
  izz="0.0038015"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.79216 0.81961 0.93333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

<link name="front_front_right"><inertial><origin xyz="2.7273E-08 8.4788E-07 0.033785" rpy="0 0 0" /><mass value="0.62345" /><inertia
    ixx="0.0021571"
    ixy="5.7178E-10"
    ixz="1.3794E-10"
    iyy="0.0021571"
    iyz="1.1818E-08"
    izz="0.0038015"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.79216 0.81961 0.93333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

  <link name="back_left"><inertial><origin xyz="-0.15140299531934 -0.076526205656618 -0.0451940468029265" rpy="0 0 0" /><mass value="0.729214138297053" /><inertia
    ixx="0.00137478227627483"
    ixy="-0.00131726895128445"
    ixz="7.25804426030585E-05"
    iyy="0.00281017626017176"
    iyz="5.18669798425697E-05"
    izz="0.00402653973335046"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/back_left.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/back_left.STL" /></geometry></collision></link>

<link name="back_back_left"><inertial><origin xyz="-0.158949747221027 -0.179818420204466 0.114374790536462" rpy="0 0 0" /><mass value="0.623450632515184" /><inertia
    ixx="0.00215710128107367"
    ixy="5.71638504760774E-10"
    ixz="1.3798296716043E-10"
    iyy="0.00215712587063426"
    iyz="1.18183958384876E-08"
    izz="0.0038014878803089"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

<link name="back_front_left"><inertial><origin xyz="-0.158949747221027 -0.179818420204466 0.114374790536462" rpy="0 0 0" /><mass value="0.623450632515184" /><inertia
    ixx="0.00215710128107367"
    ixy="5.71638504760774E-10"
    ixz="1.3798296716043E-10"
    iyy="0.00215712587063426"
    iyz="1.18183958384876E-08"
    izz="0.0038014878803089"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

<link name="back_right"><inertial><origin xyz="-0.15140299531934 -0.076526205656618 -0.0451940468029265" rpy="0 0 0" /><mass value="0.729214138297053" /><inertia
    ixx="0.00137478227627483"
    ixy="-0.00131726895128445"
    ixz="7.25804426030585E-05"
    iyy="0.00281017626017176"
    iyz="5.18669798425697E-05"
    izz="0.00402653973335046"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/front_left.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/front_left.STL" /></geometry></collision></link>

<link name="back_front_right"><inertial><origin xyz="-0.158949747221027 -0.179818420204466 0.114374790536462" rpy="0 0 0" /><mass value="0.623450632515184" /><inertia
    ixx="0.00215710128107367"
    ixy="5.71638504760774E-10"
    ixz="1.3798296716043E-10"
    iyy="0.00215712587063426"
    iyz="1.18183958384876E-08"
    izz="0.0038014878803089"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

<link name="back_back_right"><inertial><origin xyz="-0.158949747221027 -0.179818420204466 0.114374790536462" rpy="0 0 0" /><mass value="0.623450632515184" /><inertia
    ixx="0.00215710128107367"
    ixy="5.71638504760774E-10"
    ixz="1.3798296716043E-10"
    iyy="0.00215712587063426"
    iyz="1.18183958384876E-08"
    izz="0.0038014878803089"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/wheel.STL" /></geometry></collision></link>

<link name="first_joint"><inertial><origin xyz="0.0305449182518565 0.0421767894980517 -0.000713619794850737" rpy="0 0 0" /><mass value="0.638830686278263" /><inertia
    ixx="0.0011838875136232"
    ixy="-3.51721262596745E-06"
    ixz="-1.63819290540096E-07"
    iyy="0.00120175386226222"
    iyz="2.06132705695245E-05"
    izz="0.000363592396162486"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/first_joint.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/first_joint.STL" /></geometry></collision></link>

<link name="secend_joint"><inertial><origin xyz="-0.175677581187736 -0.0123314564212373 -0.0492758700829626" rpy="0 0 0" /><mass value="0.807376160366276" /><inertia
    ixx="0.000630414968330994"
    ixy="-3.82136722331278E-05"
    ixz="-1.37817925944878E-05"
    iyy="0.00117654340601428"
    iyz="-1.66765555436819E-06"
    izz="0.00131861318260476"
/></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/secend_joint.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/secend_joint.STL" /></geometry></collision></link>

<link name="third_joint"><inertial><origin xyz="0.00402861152624634 0.21164020768833 0.0345460712989879" rpy="0 0 0" /><mass value="0.626572043058301"/><inertia
    ixx="0.00106610359217973"
    ixy="7.41111575170188E-05"
    ixz="1.45189467275061E-06"
    iyy="0.00520016275295146"
    iyz="-1.11967932028121E-05"
    izz="0.00435402539580952"
  /></inertial><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/third_joint.STL" /></geometry><material name=""><color rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" /></material></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><mesh filename="package://x8_sim/meshes/third_joint.STL" /></geometry></collision></link>

<!--    joints-->

  <joint name="chassis_joint" type="fixed"><parent link="base_link" /><child link="chassis" /><origin xyz="0 0 0" rpy="0 0 0" /></joint>
  <joint name="front_left_joint" type="continuous"><origin xyz="0.12 0.1045 0" rpy="1.5708 0.49596 -3.1416" /><parent link="chassis" /><child link="front_left" /><axis xyz="0 0 1" /></joint>
  <joint name="front_front_left_joint" type="continuous"><origin xyz="-0.211082924841909 -0.114210327204614 0.0805897185229173" rpy="0 0 2.80586094012943" /><parent link="front_left" /><child link="front_front_left" /><axis xyz="0 0 1" /></joint>
  <joint name="front_back_left_joint" type="continuous"><origin xyz="0 0 0.08059" rpy="0 0 2.7906" /><parent link="front_left" /><child link="front_back_left" /><axis xyz="0 0 1" /><mimic joint="front_front_left_joint" multiplier="1.0" /></joint>
  <joint name="front_right_joint" type="continuous"><origin xyz="0.12 -0.1045 0" rpy="1.5708 0.49596 -3.1416" /><parent link="chassis" /><child link="front_right" /> <!-- This needs to be changed --><axis xyz="0 0 1" /></joint>
  <joint name="front_front_right_joint" type="continuous"><origin xyz="-0.211082924841909 -0.114210327204614 -0.0805897185229173" rpy="0 3.1416 0" /><parent link="front_right" /><child link="front_front_right" /><axis xyz="0 0 1" /></joint>
  <joint name="front_back_right_joint" type="continuous"><origin xyz="0 0 -0.08059" rpy="3.1416 0 0" /><parent link="front_right" /><child link="front_back_right" /><axis xyz="0 0 1" /><mimic joint="front_front_right_joint" multiplier="1.0" /></joint>
  <joint name="back_left_joint" type="continuous"><origin xyz="-0.12 0.1045 0" rpy="1.5708 0.49596 0" /><parent link="chassis" /><child link="back_left" /> <!-- This needs to be changed --><axis xyz="0 0 1" /></joint>
  <joint name="back_back_left_joint" type="continuous"><origin xyz="-0.211082924841909 -0.114210327204614 -0.0805897185229173" rpy="3.14159265358979 0 1.342884492008" /><parent link="back_left" /><child link="back_back_left" /><axis xyz="0 0 1" /></joint>
  <joint name="back_front_left_joint" type="continuous"><origin xyz="0.0 0.0 -0.0805897185229173" rpy="3.14159265358979 0 1.342884492008" /><parent link="back_left" /><child link="back_front_left" /><axis xyz="0 0 1" /><mimic joint="back_back_left_joint" multiplier="1.0" /></joint>
  <joint name="back_right_joint" type="continuous"><origin xyz="-0.12 -0.1045 0" rpy="1.5708 0.49596 0" /><parent link="chassis" /><child link="back_right" /> <!-- This needs to be changed --><axis xyz="0 0 1" /></joint>
  <joint name="back_front_right_joint" type="continuous"><origin xyz="0.0 0.0 0.0805897185229173" rpy="0.0 0.0 0.0" /><parent link="back_right" /><child link="back_front_right" /><axis xyz="0 0 1" /><mimic joint="back_back_right_joint" multiplier="1.0" /></joint>
  <joint name="back_back_right_joint" type="continuous"><origin xyz="-0.211082924841909 -0.114210327204614 0.0805897185229173" rpy="0.0 0.0 0.0" /><parent link="back_right" /><child link="back_back_right" /><axis xyz="0 0 1" /></joint>
  <joint name="first_joint_arm" type="continuous"><origin xyz="0.1 0 0.177944863728323" rpy="1.5707963267949 0 0" /><parent link="chassis" /><child link="first_joint" /><axis xyz="0 1 0" /></joint>
  <joint name="secend_joint_arm" type="continuous"><origin xyz="0 0.0521726509171591 -0.0459999749228997" rpy="0 0 0.01402909672053" /><parent link="first_joint" /><child link="secend_joint" /><axis xyz="0 0 1" /></joint>
  <joint name="third_joint_arm" type="continuous"><origin xyz="-0.408003696653826 -0.0285303963662949 0" rpy="0 0 0.00396339972398549" /><parent link="secend_joint" /><child link="third_joint" /><axis xyz="0 0 1" /></joint>

<!--gazebo-->

  <gazebo reference="chassis"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/Black</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="front_left"><mu1>1.5</mu1><mu2>1.5</mu2><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="front_front_left"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/White</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="front_back_left"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/White</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="front_right"><mu1>1.5</mu1><mu2>1.5</mu2><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="front_front_right"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/White</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="front_back_right"><mu1>1.5</mu1><mu2>1.5</mu2><self_collide>1</self_collide><material>Gazebo/White</material><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="back_left"><mu1>1.5</mu1><mu2>1.5</mu2><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="back_back_left"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/White</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="back_front_left"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/White</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="back_right"><mu1>1.5</mu1><mu2>1.5</mu2><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="back_back_right"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/White</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="back_front_right"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/White</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="first_joint"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/Blue</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="secend_joint"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/Blue</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>
  <gazebo reference="third_joint"><mu1>1.5</mu1><mu2>1.5</mu2><material>Gazebo/Blue</material><self_collide>1</self_collide><kp value="100000.0" /><kd value="1.0" /></gazebo>

<plugin name="x8_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros><remapping>~/out:=joint_states</remapping></ros>
<update_rate>30</update_rate>
<joint_name>front_front_left_joint</joint_name>
<joint_name>front_front_right_joint</joint_name>
<joint_name>back_back_left_joint</joint_name>
<joint_name>back_back_right_joint</joint_name>
<joint_name>front_left_joint</joint_name>
<joint_name>front_right_joint</joint_name>
<joint_name>back_left_joint</joint_name>
<joint_name>back_right_joint</joint_name>
</plugin>

<ros2_control name="GazeboSystem" type="system">
  <hardware>
    <plugin>gazebo_ros2_control/GazeboSystem</plugin>
  </hardware>

  <!-- Joints with position control -->
  <joint name="front_left_joint">
    <command_interface name="position">
      <param name="min">-3.14</param>
      <param name="max">3.14</param>
    </command_interface>
    <state_interface name="position">
      <param name="initial_value">0</param>
    </state_interface>
    <state_interface name="velocity"/>
  </joint>

  <joint name="front_right_joint">
    <command_interface name="position">
      <param name="min">-3.14</param>
      <param name="max">3.14</param>
    </command_interface>
    <state_interface name="position">
      <param name="initial_value">0</param>
    </state_interface>
    <state_interface name="velocity"/>
  </joint>

  <joint name="back_right_joint">
    <command_interface name="position">
      <param name="min">-3.14</param>
      <param name="max">3.14</param>
    </command_interface>
    <state_interface name="position">
      <param name="initial_value">0</param>
    </state_interface>
    <state_interface name="velocity"/>
  </joint>

  <joint name="back_left_joint">
    <command_interface name="position">
      <param name="min">-3.14</param>
      <param name="max">3.14</param>
    </command_interface>
    <state_interface name="position">
      <param name="initial_value">0</param>
    </state_interface>
    <state_interface name="velocity"/>
  </joint>

  <!-- Joints with velocity control -->
  <joint name="front_front_left_joint">
    <command_interface name="velocity">
      <param name="min">-10</param>
      <param name="max">10</param>
    </command_interface>
    <state_interface name="velocity"/>
    <state_interface name="position"/>
  </joint>

  <joint name="front_front_right_joint">
    <command_interface name="velocity">
      <param name="min">-10</param>
      <param name="max">10</param>
    </command_interface>
    <state_interface name="velocity"/>
    <state_interface name="position"/>
  </joint>

  <joint name="back_back_left_joint">
    <command_interface name="velocity">
      <param name="min">-10</param>
      <param name="max">10</param>
    </command_interface>
    <state_interface name="velocity"/>
    <state_interface name="position"/>
  </joint>

  <joint name="back_back_right_joint">
    <command_interface name="velocity">
      <param name="min">-10</param>
      <param name="max">10</param>
    </command_interface>
    <state_interface name="velocity"/>
    <state_interface name="position"/>
  </joint>
</ros2_control>

<gazebo>
  <plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
    <parameters>/home/naor/Desktop/naor/work/x8_c++/src/x8_sim/config/my_controllers.yaml</parameters>
  </plugin>
</gazebo>

</robot>

the launch file - at this state i run 2 launch file one for the gazebo and one for the controllers

import os
from pathlib import Path
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable, IncludeLaunchDescription
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
from launch.substitutions import Command, LaunchConfiguration
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.parameter_descriptions import ParameterValue

def generate_launch_description():
    # Define package directories
    x8_sim_dir = get_package_share_directory("x8_sim")
    gazebo_ros_pkg = get_package_share_directory('gazebo_ros')

    # Declare the model argument to specify the path to the URDF file
    model_arg = DeclareLaunchArgument(
        name="model",
        default_value=str(Path(x8_sim_dir) / "urdf" / "robot.urdf.xacro"),
        description="Absolute path to robot URDF file"
    )

    # Use xacro to process the URDF file and load the robot description parameter
    robot_description = ParameterValue(
        Command(["xacro ", LaunchConfiguration("model")]),  # Ensure proper command usage
        value_type=str
    )

    # Node to publish the robot state
    robot_state_publisher = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        parameters=[{"robot_description": robot_description}],
        output="screen"
    )

    # Set the environment variable for Gazebo model path (updated for model directory)
    gazebo_resource_path = SetEnvironmentVariable(
        name="GAZEBO_MODEL_PATH",
        value=str(Path(x8_sim_dir) / "models")  # Updated to point to the models directory
    )

    # Include the Gazebo server launch file
    start_gazebo_server_cmd = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            str(Path(gazebo_ros_pkg) / 'launch' / 'gazebo.launch.py')
        ),
        launch_arguments={'world': LaunchConfiguration('world')}.items()
    )

    # Spawn the robot in Gazebo using the robot_description
    spawn_robot = Node(
        package="gazebo_ros",
        executable="spawn_entity.py",
        arguments=["-topic", "/robot_description", "-entity", "x8_robot"],
        output="screen"
    )

    # Declare the world file argument
    declare_world_cmd = DeclareLaunchArgument(
        name='world',
        default_value=str(Path('/home/naor/Desktop/naor/work/x8_c++/src/x8_sim/worlds/obstacle.world')),
        description='Path to the Gazebo world file'
    )

    # Return the complete LaunchDescription
    return LaunchDescription([
        declare_world_cmd,
        model_arg,
        robot_state_publisher,
        gazebo_resource_path,
        start_gazebo_server_cmd,
        spawn_robot
    ])

and for the control:

from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():

    joint_state_broadcaster_spawner = Node(
        package="controller_manager",
        executable="spawner",
        arguments=[
            "joint_state_broadcaster",
            "--controller-manager",
            "/controller_manager"
        ],
        output="screen"
    )

    position_controller = Node(
        package="controller_manager",
        executable="spawner",
        arguments=[
            "position_controller",
            "--controller-manager",
            "/controller_manager"
        ],
        output="screen"
    )

    velocity_controller = Node(
        package="controller_manager",
        executable="spawner",
        arguments=[
            "velocity_controller",
            "--controller-manager",
            "/controller_manager"
        ],
        output="screen"
    )

    return LaunchDescription([
        joint_state_broadcaster_spawner,
        position_controller,
        velocity_controller
    ])

the yaml file for the controlers

controller_manager:
  ros__parameters:
    update_rate: 100  # Hz
    use_sim_time: true

    # Joint State Broadcaster
    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    # Position and Velocity Controllers
    position_controller:
      type: position_controllers/JointGroupPositionController

    velocity_controller:
      type: velocity_controllers/JointGroupVelocityController

    position_controller:
      ros__parameters:
        joints:
          - back_left_joint
          - back_right_joint
          - front_left_joint
          - front_right_joint
        command_interfaces:
          - position
        state_interfaces:
          - position
          - velocity

    velocity_controller:
      ros__parameters:
        joints:
          - back_back_left_joint
          - back_back_right_joint
          - front_front_left_joint
          - front_front_right_joint
        command_interfaces:
          - velocity
        state_interfaces:
          - position
          - velocity

all the partf of the gzebo work but i didnt understand the problem of the unconfigured thanks for the help

christophfroehlich commented 1 day ago

please add the console output from both launch files, or we can't help you.

naorwaiss commented 1 day ago

ok so the first launch file - the gazebo one

ASUS-TUF-Gaming-F15-FX507VV-FX507VV:~/Desktop/naor/work/x8_c++$ ros2 launch x8_sim robot_gazebo_launch.py 
[INFO] [launch]: All log files can be found below /home/naor/.ros/log/2024-10-21-14-02-22-432865-naor-ASUS-TUF-Gaming-F15-FX507VV-FX507VV-133403
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [gzserver-1]: process started with pid [133404]
[INFO] [gzclient-2]: process started with pid [133406]
[INFO] [robot_state_publisher-3]: process started with pid [133408]
[robot_state_publisher-3] [INFO] [1729508542.938452285] [robot_state_publisher]: got segment back_back_left
[robot_state_publisher-3] [INFO] [1729508542.938522009] [robot_state_publisher]: got segment back_back_right
[robot_state_publisher-3] [INFO] [1729508542.938527323] [robot_state_publisher]: got segment back_front_left
[robot_state_publisher-3] [INFO] [1729508542.938530274] [robot_state_publisher]: got segment back_front_right
[robot_state_publisher-3] [INFO] [1729508542.938533389] [robot_state_publisher]: got segment back_left
[robot_state_publisher-3] [INFO] [1729508542.938536096] [robot_state_publisher]: got segment back_right
[robot_state_publisher-3] [INFO] [1729508542.938538807] [robot_state_publisher]: got segment base_link
[robot_state_publisher-3] [INFO] [1729508542.938541497] [robot_state_publisher]: got segment chassis
[robot_state_publisher-3] [INFO] [1729508542.938544111] [robot_state_publisher]: got segment first_joint
[robot_state_publisher-3] [INFO] [1729508542.938546832] [robot_state_publisher]: got segment front_back_left
[robot_state_publisher-3] [INFO] [1729508542.938549454] [robot_state_publisher]: got segment front_back_right
[robot_state_publisher-3] [INFO] [1729508542.938552125] [robot_state_publisher]: got segment front_front_left
[robot_state_publisher-3] [INFO] [1729508542.938554666] [robot_state_publisher]: got segment front_front_right
[robot_state_publisher-3] [INFO] [1729508542.938557399] [robot_state_publisher]: got segment front_left
[robot_state_publisher-3] [INFO] [1729508542.938559988] [robot_state_publisher]: got segment front_right
[robot_state_publisher-3] [INFO] [1729508542.938562695] [robot_state_publisher]: got segment secend_joint
[robot_state_publisher-3] [INFO] [1729508542.938565447] [robot_state_publisher]: got segment third_joint
[INFO] [spawn_entity.py-4]: process started with pid [133620]
[spawn_entity.py-4] [INFO] [1729508548.230213235] [spawn_entity]: Spawn Entity started
[spawn_entity.py-4] [INFO] [1729508548.230471288] [spawn_entity]: Loading entity XML from file /tmp/tmp43dwaagn.urdf
[spawn_entity.py-4] [INFO] [1729508548.231268255] [spawn_entity]: Waiting for service /spawn_entity, timeout = 30
[spawn_entity.py-4] [INFO] [1729508548.231469206] [spawn_entity]: Waiting for service /spawn_entity
[spawn_entity.py-4] [INFO] [1729508548.234092137] [spawn_entity]: Calling service /spawn_entity
[spawn_entity.py-4] [INFO] [1729508548.442455116] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [x8_robot]
[INFO] [spawn_entity.py-4]: process has finished cleanly [pid 133620]
[gzserver-1] [INFO] [1729508552.745815449] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin
[gzserver-1] [INFO] [1729508552.748285404] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: /
[gzserver-1] [INFO] [1729508552.748517256] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control
[gzserver-1] [INFO] [1729508552.750214586] [gazebo_ros2_control]: connected to service!! robot_state_publisher
[gzserver-1] [INFO] [1729508552.750779725] [gazebo_ros2_control]: Received urdf from param server, parsing...
[gzserver-1] [INFO] [1729508552.750810170] [gazebo_ros2_control]: Loading parameter files /home/naor/Desktop/naor/work/x8_c++/src/x8_sim/config/my_controllers.yaml
[gzserver-1] [INFO] [1729508552.759241529] [gazebo_ros2_control]: Loading joint: front_left_joint
[gzserver-1] [INFO] [1729508552.759306482] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759313250] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759320845] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729508552.759329875] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759333516] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759336783] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759370205] [gazebo_ros2_control]: Loading joint: front_right_joint
[gzserver-1] [INFO] [1729508552.759374399] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759377392] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759380442] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729508552.759383917] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759386826] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759390085] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759398855] [gazebo_ros2_control]: Loading joint: back_right_joint
[gzserver-1] [INFO] [1729508552.759402128] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759405166] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759408159] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729508552.759411389] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759414199] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759417218] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759426519] [gazebo_ros2_control]: Loading joint: back_left_joint
[gzserver-1] [INFO] [1729508552.759429640] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759432540] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759435280] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729508552.759438426] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759441247] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759444129] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759457585] [gazebo_ros2_control]: Loading joint: front_front_left_joint
[gzserver-1] [INFO] [1729508552.759461587] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759465047] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759468545] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759471663] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759476640] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759480797] [gazebo_ros2_control]: Loading joint: front_front_right_joint
[gzserver-1] [INFO] [1729508552.759484127] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759487096] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759490127] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759492970] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759497592] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759501555] [gazebo_ros2_control]: Loading joint: back_back_left_joint
[gzserver-1] [INFO] [1729508552.759504508] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759507390] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759510254] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759513009] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759516859] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759520643] [gazebo_ros2_control]: Loading joint: back_back_right_joint
[gzserver-1] [INFO] [1729508552.759523533] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729508552.759526264] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759529017] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729508552.759573105] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729508552.759577423] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729508552.759617775] [resource_manager]: Initialize hardware 'GazeboSystem' 
[gzserver-1] [INFO] [1729508552.759710743] [resource_manager]: Successful initialization of hardware 'GazeboSystem'
[gzserver-1] [INFO] [1729508552.759771241] [resource_manager]: 'configure' hardware 'GazeboSystem' 
[gzserver-1] [INFO] [1729508552.759777161] [resource_manager]: Successful 'configure' of hardware 'GazeboSystem'
[gzserver-1] [INFO] [1729508552.759783142] [resource_manager]: 'activate' hardware 'GazeboSystem' 
[gzserver-1] [INFO] [1729508552.759786213] [resource_manager]: Successful 'activate' of hardware 'GazeboSystem'
[gzserver-1] [INFO] [1729508552.759856009] [gazebo_ros2_control]: Loading controller_manager
[gzserver-1] [INFO] [1729508552.770777734] [gazebo_ros2_control]: Loaded gazebo_ros2_control.

and the other launch file for the controller

naor@naor-ASUS-TUF-Gaming-F15-FX507VV-FX507VV:~/Desktop/naor/work/x8_c++$ ros2 launch x8_sim controller.launch.py 
[INFO] [launch]: All log files can be found below /home/naor/.ros/log/2024-10-21-14-03-25-887834-naor-ASUS-TUF-Gaming-F15-FX507VV-FX507VV-133858
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [spawner-1]: process started with pid [133859]
[INFO] [spawner-2]: process started with pid [133861]
[INFO] [spawner-3]: process started with pid [133863]
[spawner-2] [INFO] [1729508606.543039117] [spawner_position_controller]: Loaded position_controller
[spawner-1] [INFO] [1729508606.573705941] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster
[spawner-2] [ERROR] [1729508606.594655767] [spawner_position_controller]: Failed to configure controller
[spawner-3] [INFO] [1729508606.604764917] [spawner_velocity_controller]: Loaded velocity_controller
[spawner-3] [ERROR] [1729508606.625029620] [spawner_velocity_controller]: Failed to configure controller
[spawner-1] [INFO] [1729508606.692269460] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[ERROR] [spawner-2]: process has died [pid 133861, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner position_controller --controller-manager /controller_manager --ros-args'].
[ERROR] [spawner-3]: process has died [pid 133863, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner velocity_controller --controller-manager /controller_manager --ros-args'].
[INFO] [spawner-1]: process has finished cleanly [pid 133859]
christophfroehlich commented 1 day ago

Isn't there any additional output in the gazebo launch file after you launch the controller one?

naorwaiss commented 22 hours ago

umm this is the the gazebo after the launch of the controller

naor@naor-ASUS-TUF-Gaming-F15-FX507VV-FX507VV:~/Desktop/naor/work/x8_c++$ ros2 launch x8_sim robot_gazebo_launch.py 
[INFO] [launch]: All log files can be found below /home/naor/.ros/log/2024-10-21-16-37-59-463960-naor-ASUS-TUF-Gaming-F15-FX507VV-FX507VV-9544
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [gzserver-1]: process started with pid [9545]
[INFO] [gzclient-2]: process started with pid [9547]
[INFO] [robot_state_publisher-3]: process started with pid [9549]
[robot_state_publisher-3] [INFO] [1729517880.025390102] [robot_state_publisher]: got segment back_back_left
[robot_state_publisher-3] [INFO] [1729517880.025471489] [robot_state_publisher]: got segment back_back_right
[robot_state_publisher-3] [INFO] [1729517880.025478050] [robot_state_publisher]: got segment back_front_left
[robot_state_publisher-3] [INFO] [1729517880.025481602] [robot_state_publisher]: got segment back_front_right
[robot_state_publisher-3] [INFO] [1729517880.025484873] [robot_state_publisher]: got segment back_left
[robot_state_publisher-3] [INFO] [1729517880.025488129] [robot_state_publisher]: got segment back_right
[robot_state_publisher-3] [INFO] [1729517880.025491229] [robot_state_publisher]: got segment base_link
[robot_state_publisher-3] [INFO] [1729517880.025494583] [robot_state_publisher]: got segment chassis
[robot_state_publisher-3] [INFO] [1729517880.025497734] [robot_state_publisher]: got segment first_joint
[robot_state_publisher-3] [INFO] [1729517880.025500743] [robot_state_publisher]: got segment front_back_left
[robot_state_publisher-3] [INFO] [1729517880.025503820] [robot_state_publisher]: got segment front_back_right
[robot_state_publisher-3] [INFO] [1729517880.025506845] [robot_state_publisher]: got segment front_front_left
[robot_state_publisher-3] [INFO] [1729517880.025509881] [robot_state_publisher]: got segment front_front_right
[robot_state_publisher-3] [INFO] [1729517880.025512870] [robot_state_publisher]: got segment front_left
[robot_state_publisher-3] [INFO] [1729517880.025520998] [robot_state_publisher]: got segment front_right
[robot_state_publisher-3] [INFO] [1729517880.025525380] [robot_state_publisher]: got segment secend_joint
[robot_state_publisher-3] [INFO] [1729517880.025528525] [robot_state_publisher]: got segment third_joint
[INFO] [spawn_entity.py-4]: process started with pid [9792]
[spawn_entity.py-4] [INFO] [1729517885.639993097] [spawn_entity]: Spawn Entity started
[spawn_entity.py-4] [INFO] [1729517885.640192442] [spawn_entity]: Loading entity XML from file /tmp/tmpzq4skibo.urdf
[spawn_entity.py-4] [INFO] [1729517885.641882440] [spawn_entity]: Waiting for service /spawn_entity, timeout = 30
[spawn_entity.py-4] [INFO] [1729517885.642067021] [spawn_entity]: Waiting for service /spawn_entity
[spawn_entity.py-4] [INFO] [1729517885.646910953] [spawn_entity]: Calling service /spawn_entity
[spawn_entity.py-4] [INFO] [1729517885.942311731] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [x8_robot]
[INFO] [spawn_entity.py-4]: process has finished cleanly [pid 9792]
[gzserver-1] [INFO] [1729517890.326004828] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin
[gzserver-1] [INFO] [1729517890.328329742] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: /
[gzserver-1] [INFO] [1729517890.328534164] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control
[gzserver-1] [INFO] [1729517890.329764317] [gazebo_ros2_control]: connected to service!! robot_state_publisher
[gzserver-1] [INFO] [1729517890.330322988] [gazebo_ros2_control]: Received urdf from param server, parsing...
[gzserver-1] [INFO] [1729517890.330345722] [gazebo_ros2_control]: Loading parameter files /home/naor/Desktop/naor/work/x8_c++/src/x8_sim/config/my_controllers.yaml
[gzserver-1] [INFO] [1729517890.340875227] [gazebo_ros2_control]: Loading joint: front_left_joint
[gzserver-1] [INFO] [1729517890.340951735] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.340959835] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.340968227] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729517890.340975445] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.340979227] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.340982389] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341192074] [gazebo_ros2_control]: Loading joint: front_right_joint
[gzserver-1] [INFO] [1729517890.341196584] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.341199804] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341203318] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729517890.341206794] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341209917] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.341212951] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341227727] [gazebo_ros2_control]: Loading joint: back_right_joint
[gzserver-1] [INFO] [1729517890.341230895] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.341233973] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341236983] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729517890.341240187] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341243393] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.341246352] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341261655] [gazebo_ros2_control]: Loading joint: back_left_joint
[gzserver-1] [INFO] [1729517890.341264712] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.341267659] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341270553] [gazebo_ros2_control]:                        found initial value: 0.000000
[gzserver-1] [INFO] [1729517890.341273730] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341276626] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.341279564] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341288449] [gazebo_ros2_control]: Loading joint: front_front_left_joint
[gzserver-1] [INFO] [1729517890.341291612] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.341294501] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341298068] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341301569] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.341305883] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341310079] [gazebo_ros2_control]: Loading joint: front_front_right_joint
[gzserver-1] [INFO] [1729517890.341313418] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.341316467] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341319404] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341322293] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.341326107] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341329522] [gazebo_ros2_control]: Loading joint: back_back_left_joint
[gzserver-1] [INFO] [1729517890.341332567] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.341335470] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341338496] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341341340] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.341345183] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341348680] [gazebo_ros2_control]: Loading joint: back_back_right_joint
[gzserver-1] [INFO] [1729517890.341351632] [gazebo_ros2_control]:       State:
[gzserver-1] [INFO] [1729517890.341354470] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341357332] [gazebo_ros2_control]:                position
[gzserver-1] [INFO] [1729517890.341396329] [gazebo_ros2_control]:       Command:
[gzserver-1] [INFO] [1729517890.341401045] [gazebo_ros2_control]:                velocity
[gzserver-1] [INFO] [1729517890.341452691] [resource_manager]: Initialize hardware 'GazeboSystem' 
[gzserver-1] [INFO] [1729517890.341623792] [resource_manager]: Successful initialization of hardware 'GazeboSystem'
[gzserver-1] [INFO] [1729517890.341729193] [resource_manager]: 'configure' hardware 'GazeboSystem' 
[gzserver-1] [INFO] [1729517890.341740109] [resource_manager]: Successful 'configure' of hardware 'GazeboSystem'
[gzserver-1] [INFO] [1729517890.341746316] [resource_manager]: 'activate' hardware 'GazeboSystem' 
[gzserver-1] [INFO] [1729517890.341749895] [resource_manager]: Successful 'activate' of hardware 'GazeboSystem'
[gzserver-1] [INFO] [1729517890.341856347] [gazebo_ros2_control]: Loading controller_manager
[gzserver-1] [INFO] [1729517890.359326652] [gazebo_ros2_control]: Loaded gazebo_ros2_control.
[gzserver-1] [INFO] [1729517890.528835379] [controller_manager]: Loading controller 'joint_state_broadcaster'
[gzserver-1] [INFO] [1729517890.550574469] [controller_manager]: Loading controller 'velocity_controller'
[gzserver-1] [INFO] [1729517890.602156462] [controller_manager]: Loading controller 'position_controller'
[gzserver-1] [INFO] [1729517890.633254873] [controller_manager]: Configuring controller 'joint_state_broadcaster'
[gzserver-1] [INFO] [1729517890.633479022] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[gzserver-1] [INFO] [1729517890.661671672] [controller_manager]: Configuring controller 'velocity_controller'
[gzserver-1] [ERROR] [1729517890.661791468] [velocity_controller]: 'joints' parameter was empty
[gzserver-1] [WARN] [1729517890.661829242] [velocity_controller]: Error occurred while doing error handling.
[gzserver-1] [ERROR] [1729517890.661875180] [controller_manager]: After configuring, controller 'velocity_controller' is in state 'unconfigured' , expected inactive.
[gzserver-1] [INFO] [1729517890.661944977] [controller_manager]: Configuring controller 'position_controller'
[gzserver-1] [ERROR] [1729517890.661958298] [position_controller]: 'joints' parameter was empty
[gzserver-1] [WARN] [1729517890.661967130] [position_controller]: Error occurred while doing error handling.
[gzserver-1] [ERROR] [1729517890.661972750] [controller_manager]: After configuring, controller 'position_controller' is in state 'unconfigured' , expected inactive.