husarion / rosbot_ros

ROS packages for ROSbot 2, 2R and 2 PRO
122 stars 62 forks source link

missing link for depth camera in simulation, broken robot_description #55

Closed Neathle closed 11 months ago

Neathle commented 1 year ago

I am simulating the ROSBOT2 in humble, using the docker image provided, and using the simulation.launch.py provided as well in the repo. When I launch the simulation, everything works correctly, except the depth camera, which appears to be missing a link to the rest of the robot. The depth camera has created its own tree: /rosbot/base_link/orbbec_astra_camera. Instead of using the depth link to publish. image image

Robot_description is also broken, as it can be seen in the image. I tried with rviz2 as well and it simply doesn't display the robot. I solved the first issue by manually linking both frames in the /tf_static topic, but this should be corrected. I include the generated urdf from doing xacro /ros2_ws/src/rosbot_description/urdf/rosbot.urdf.xacro:

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from /ros2_ws/src/rosbot_description/urdf/rosbot.urdf.xacro | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="rosbot">
  <link name="base_link"/>
  <joint name="base_to_body_joint" type="fixed">
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0425"/>
    <parent link="base_link"/>
    <child link="body_link"/>
  </joint>
  <link name="body_link">
    <visual>
      <geometry>
        <mesh filename="file:///ros2_ws/install/rosbot_description/share/rosbot_description/meshes/body.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <origin rpy="1.5707963267948966 0.0 1.5707963267948966" xyz="0.0 0.0 -0.0173"/>
      <material name="White">
        <color rgba="1.0 1.0 1.0 1.0"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <box size="0.197 0.150 0.080"/>
      </geometry>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.02"/>
    </collision>
    <inertial>
      <mass value="1.728"/>
      <inertia ixx="0.004162" ixy="0.0" ixz="0.0" iyy="0.00651" iyz="0.0" izz="0.008828"/>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.02"/>
    </inertial>
  </link>
  <gazebo reference="body_link">
    <material>Gazebo/White</material>
  </gazebo>
  <joint name="body_to_cover_joint" type="fixed">
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0603"/>
    <parent link="body_link"/>
    <child link="cover_link"/>
  </joint>
  <link name="cover_link">
    <visual>
      <geometry>
        <mesh filename="file:///ros2_ws/install/rosbot_description/share/rosbot_description/meshes/cover.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <origin rpy="1.5707963267948966 0.0 1.5707963267948966" xyz="0.0 0.0 -0.002"/>
      <material name="Red">
        <color rgba="0.8 0.0 0.0 1.0"/>
      </material>
    </visual>
    <gazebo reference="cover_link">
      <material>Gazebo/Red</material>
    </gazebo>
  </link>
  <joint name="body_to_imu_joint" type="fixed">
    <origin rpy="0.0 0.0 0.0" xyz="0.003 -0.0495 0.04332"/>
    <parent link="body_link"/>
    <child link="imu_link"/>
  </joint>
  <link name="imu_link"/>
  <joint name="body_to_camera_joint" type="fixed">
    <origin rpy="0.0 0.0 0.0" xyz="-0.0141 0.0 0.125"/>
    <parent link="body_link"/>
    <child link="camera_link"/>
  </joint>
  <link name="camera_link"/>
  <joint name="body_link_fl_range_joint" type="fixed">
    <origin rpy="0.0 0.0 0.2181661564992912" xyz="0.0926  0.05 0.015"/>
    <parent link="body_link"/>
    <child link="fl_range"/>
  </joint>
  <link name="fl_range"/>
  <joint name="body_link_fr_range_joint" type="fixed">
    <origin rpy="0.0 0.0 -0.2181661564992912" xyz="0.0926 -0.05 0.015"/>
    <parent link="body_link"/>
    <child link="fr_range"/>
  </joint>
  <link name="fr_range"/>
  <joint name="body_link_rl_range_joint" type="fixed">
    <origin rpy="0.0 0.0 2.923426497090502" xyz="-0.0926 0.05 0.0115"/>
    <parent link="body_link"/>
    <child link="rl_range"/>
  </joint>
  <link name="rl_range"/>
  <joint name="body_link_rr_range_joint" type="fixed">
    <origin rpy="0.0 0.0 3.3597588100890845" xyz="-0.0926 -0.05 0.0115"/>
    <parent link="body_link"/>
    <child link="rr_range"/>
  </joint>
  <link name="rr_range"/>
  <joint name="fr_wheel_joint" type="continuous">
    <parent link="body_link"/>
    <child link="fr_wheel_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.053 -0.096 0.0"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="1.5" velocity="5.0"/>
    <dynamics damping="0.001" friction="0.001"/>
  </joint>
  <link name="fr_wheel_link">
    <visual>
      <geometry>
        <mesh filename="file:///ros2_ws/install/rosbot_description/share/rosbot_description/meshes/wheel_a.dae" scale="1.0 1.0 1.0"/>
      </geometry>
      <origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.0"/>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.036" radius="0.0425"/>
      </geometry>
      <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
    </collision>
    <inertial>
      <mass value="0.074"/>
      <inertia ixx="4.1e-05" ixy="0.0" ixz="0.0" iyy="6.7e-05" iyz="0.0" izz="4.1e-05"/>
    </inertial>
  </link>
  <gazebo reference="fr_wheel_link" xmlns:ignition="http://ignitionrobotics.org/schema">
    <collision>
      <surface>
        <friction>
          <ode>
            <mu>1.0</mu>
            <mu2>0.0</mu2>
            <fdir1 ignition:expressed_in="base_link">1.0 1.0 0.0</fdir1>
          </ode>
        </friction>
      </surface>
    </collision>
  </gazebo>
  <joint name="fl_wheel_joint" type="continuous">
    <parent link="body_link"/>
    <child link="fl_wheel_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="0.053 0.096 0.0"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="1.5" velocity="5.0"/>
    <dynamics damping="0.001" friction="0.001"/>
  </joint>
  <link name="fl_wheel_link">
    <visual>
      <geometry>
        <mesh filename="file:///ros2_ws/install/rosbot_description/share/rosbot_description/meshes/wheel_b.dae" scale="1.0 1.0 1.0"/>
      </geometry>
      <origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.0"/>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.036" radius="0.0425"/>
      </geometry>
      <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
    </collision>
    <inertial>
      <mass value="0.074"/>
      <inertia ixx="4.1e-05" ixy="0.0" ixz="0.0" iyy="6.7e-05" iyz="0.0" izz="4.1e-05"/>
    </inertial>
  </link>
  <gazebo reference="fl_wheel_link" xmlns:ignition="http://ignitionrobotics.org/schema">
    <collision>
      <surface>
        <friction>
          <ode>
            <mu>1.0</mu>
            <mu2>0.0</mu2>
            <fdir1 ignition:expressed_in="base_link">1.0 -1.0 0.0</fdir1>
          </ode>
        </friction>
      </surface>
    </collision>
  </gazebo>
  <joint name="rl_wheel_joint" type="continuous">
    <parent link="body_link"/>
    <child link="rl_wheel_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="-0.053 0.096 0.0"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="1.5" velocity="5.0"/>
    <dynamics damping="0.001" friction="0.001"/>
  </joint>
  <link name="rl_wheel_link">
    <visual>
      <geometry>
        <mesh filename="file:///ros2_ws/install/rosbot_description/share/rosbot_description/meshes/wheel_a.dae" scale="1.0 1.0 1.0"/>
      </geometry>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.036" radius="0.0425"/>
      </geometry>
      <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
    </collision>
    <inertial>
      <mass value="0.074"/>
      <inertia ixx="4.1e-05" ixy="0.0" ixz="0.0" iyy="6.7e-05" iyz="0.0" izz="4.1e-05"/>
    </inertial>
  </link>
  <gazebo reference="rl_wheel_link" xmlns:ignition="http://ignitionrobotics.org/schema">
    <collision>
      <surface>
        <friction>
          <ode>
            <mu>1.0</mu>
            <mu2>0.0</mu2>
            <fdir1 ignition:expressed_in="base_link">1.0 1.0 0.0</fdir1>
          </ode>
        </friction>
      </surface>
    </collision>
  </gazebo>
  <joint name="rr_wheel_joint" type="continuous">
    <parent link="body_link"/>
    <child link="rr_wheel_link"/>
    <origin rpy="0.0 0.0 0.0" xyz="-0.053 -0.096 0.0"/>
    <axis xyz="0.0 1.0 0.0"/>
    <limit effort="1.5" velocity="5.0"/>
    <dynamics damping="0.001" friction="0.001"/>
  </joint>
  <link name="rr_wheel_link">
    <visual>
      <geometry>
        <mesh filename="file:///ros2_ws/install/rosbot_description/share/rosbot_description/meshes/wheel_b.dae" scale="1.0 1.0 1.0"/>
      </geometry>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.036" radius="0.0425"/>
      </geometry>
      <origin rpy="1.5707963267948966 0.0 0.0" xyz="0.0 0.0 0.0"/>
    </collision>
    <inertial>
      <mass value="0.074"/>
      <inertia ixx="4.1e-05" ixy="0.0" ixz="0.0" iyy="6.7e-05" iyz="0.0" izz="4.1e-05"/>
    </inertial>
  </link>
  <gazebo reference="rr_wheel_link" xmlns:ignition="http://ignitionrobotics.org/schema">
    <collision>
      <surface>
        <friction>
          <ode>
            <mu>1.0</mu>
            <mu2>0.0</mu2>
            <fdir1 ignition:expressed_in="base_link">1.0 -1.0 0.0</fdir1>
          </ode>
        </friction>
      </surface>
    </collision>
  </gazebo>
  <ros2_control name="imu" type="sensor">
    <hardware>
      <plugin>rosbot_hardware_interfaces/RosbotImuSensor</plugin>
      <param name="connection_timeout_ms">120000</param>
      <param name="connection_check_period_ms">500</param>
    </hardware>
    <sensor name="imu">
      <state_interface name="orientation.x"/>
      <state_interface name="orientation.y"/>
      <state_interface name="orientation.z"/>
      <state_interface name="orientation.w"/>
      <state_interface name="angular_velocity.x"/>
      <state_interface name="angular_velocity.y"/>
      <state_interface name="angular_velocity.z"/>
      <state_interface name="linear_acceleration.x"/>
      <state_interface name="linear_acceleration.y"/>
      <state_interface name="linear_acceleration.z"/>
    </sensor>
  </ros2_control>
  <ros2_control name="wheels" type="system">
    <hardware>
      <plugin>rosbot_hardware_interfaces/RosbotSystem</plugin>
      <param name="connection_timeout_ms">120000</param>
      <param name="connection_check_period_ms">500</param>
      <!-- order of velocity commands to be published in motors_cmd Float32MultiArray msg -->
      <param name="velocity_command_joint_order">
                rr_wheel_joint,
                rl_wheel_joint,
                fr_wheel_joint,
                fl_wheel_joint
          </param>
    </hardware>
    <joint name="fl_wheel_joint">
      <command_interface name="velocity"/>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
    </joint>
    <joint name="fr_wheel_joint">
      <command_interface name="velocity"/>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
    </joint>
    <joint name="rl_wheel_joint">
      <command_interface name="velocity"/>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
    </joint>
    <joint name="rr_wheel_joint">
      <command_interface name="velocity"/>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
    </joint>
  </ros2_control>
  <joint name="cover_to_slamtec_rplidar_a2_joint" type="fixed">
    <origin rpy="0.0 0.0 0.0" xyz="0.02 0.0 0.0"/>
    <parent link="cover_link"/>
    <child link="slamtec_rplidar_a2_link"/>
  </joint>
  <link name="slamtec_rplidar_a2_link">
    <visual>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
      <geometry>
        <mesh filename="file:///ros2_ws/install/ros_components_description/share/ros_components_description/meshes/slamtec_rplidar_ax.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0205"/>
      <geometry>
        <cylinder length="0.041" radius="0.038"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0205"/>
      <mass value="0.190"/>
      <inertia ixx="0.000095206" ixy="0.0" ixz="0.0" iyy="0.000095206" iyz="0.0" izz="0.00013718"/>
    </inertial>
  </link>
  <joint name="slamtec_rplidar_a2_to_laser_joint" type="fixed">
    <origin rpy="0.0 0.0 3.141592653589793" xyz="0.0 0.0 0.031"/>
    <parent link="slamtec_rplidar_a2_link"/>
    <child link="laser"/>
  </joint>
  <link name="laser"/>
  <joint name="camera_to_orbbec_astra_joint" type="fixed">
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
    <parent link="camera_link"/>
    <child link="orbbec_astra_link"/>
  </joint>
  <link name="orbbec_astra_link">
    <visual>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
      <geometry>
        <mesh filename="file:///ros2_ws/install/ros_components_description/share/ros_components_description/meshes/orbbec_astra.dae"/>
      </geometry>
    </visual>
    <!-- camera module collision -->
    <collision>
      <origin rpy="0.0 0.0 0.0" xyz="0.0024999999999999988 0.0 0.034"/>
      <geometry>
        <box size="0.04 0.165 0.03"/>
      </geometry>
    </collision>
    <!-- mounting base model collision -->
    <collision>
      <origin rpy="0.0 0.0 0.0" xyz="-0.006499999999999999 0.0 0.0095"/>
      <geometry>
        <box size="0.06 0.06 0.019"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.028999999999999998"/>
      <mass value="0.300"/>
      <inertia ixx="0.00073916" ixy="0.0" ixz="0.0" iyy="0.00015435" iyz="0.0" izz="0.00077395"/>
    </inertial>
  </link>
  <joint name="orbbec_astra_to_depth_joint" type="fixed">
    <origin rpy="-1.5707963267948966 0.0 -1.5707963267948966" xyz="0.01 0.0 0.035"/>
    <parent link="orbbec_astra_link"/>
    <child link="depth"/>
  </joint>
  <link name="depth"/>
</robot>
delihus commented 1 year ago

Hi @Neathle, thank you for the report. We know about the issue with the rosbot_description. Actually it is an error in Foxglove. In rviz2 the meshes are correct. To fix this you can use our docker container with the Foxglove from https://github.com/husarion/foxglove-docker/ or you can apply the replacement of the meshes angles in the urdf.

# Changing rotation is cause by .stl files in rosbot_ros/rosbot_description. We will change it to the .dae files.
sed -i 's/rpy=\"1.5707963267948966 0.0 1.5707963267948966\"/rpy=\"0.0 0.0 1.5707963267948966\"/g' /rosbot.urdf

I will look at the depth camera plugin and find out whats wrong.

Best regards, JD

Neathle commented 1 year ago

Thank you very much! I have switched back to rviz for now, but I will try that fix to see if foxglove is viable. The problem with the depth camera is still there even in rviz.

delihus commented 12 months ago

Hi @Neathle, I looked at the issue and it seems like this problem https://github.com/gazebosim/gz-sensors/issues/239. It is on gazebo side and as I see they fixed this here https://github.com/gazebosim/gz-sensors/pull/350 but only for gz-sensors7 but we are using the ign-sensors6.

I made propose workaround for now here https://github.com/husarion/rosbot_ros/tree/ros2-ign-camera-fix. image As I see the rviz2 has issues with display the depth image in this format... image But rqt_image_viewer works perfect... image

Please inform me if the solution works for you and feel free to reach out if you need any further assistance. Best regards, JD

delihus commented 11 months ago

I'm closing due to inactivity. If the issue is still valid, please reopen it.