Skip to content

Commit

Permalink
fix gazebo sensor plugins for imu
Browse files Browse the repository at this point in the history
  • Loading branch information
eliasdc committed Jan 7, 2025
1 parent 220e8ff commit 161c0fe
Show file tree
Hide file tree
Showing 2 changed files with 32 additions and 35 deletions.
33 changes: 15 additions & 18 deletions realsense2_description/urdf/_d435i_imu_modules.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ Intel RealSense 435i camera.
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="gazebo_d435i_imu_modules" params="camera_name reference_link accel_optical_frame gyro_optical_frame">

<!-- Load parameters to model's main link-->
<gazebo reference="${reference_link}">
<gravity>1</gravity>
Expand Down Expand Up @@ -72,26 +72,23 @@ Intel RealSense 435i camera.
</z>
</linear_acceleration>
</imu>
<plugin name='${camera_name}_gyro_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/gyro/data_raw</remapping>
</ros>
<frame_name>${gyro_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
<plugin name='${camera_name}_accel_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/accel/data_raw</remapping>
</ros>
<frame_name>${accel_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
</sensor>
</gazebo>

<gazebo>
<plugin name='${camera_name}_gyro_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/camera/gyro/sample</remapping>
</ros>
<frame_name>${gyro_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
<plugin name='${camera_name}_accel_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/camera/accel/sample</remapping>
</ros>
<frame_name>${accel_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
</gazebo>

</xacro:macro>
</robot>

34 changes: 17 additions & 17 deletions realsense2_description/urdf/_d455.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,10 @@
<!--
This is the Gazebo URDF model for the Intel RealSense D455 camera
-->

<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="gazebo_d455" params="camera_name reference_link depth_optical_frame color_optical_frame infrared1_optical_frame infrared2_optical_frame publish_pointcloud:=true accel_optical_frame gyro_optical_frame" >

<xacro:macro name="gazebo_d455" params="camera_name reference_link depth_optical_frame color_optical_frame infrared1_optical_frame infrared2_optical_frame publish_pointcloud:=true accel_optical_frame gyro_optical_frame">

<!-- Load parameters to model's main link-->
<xacro:property name="deg_to_rad" value="0.01745329251994329577" />
Expand Down Expand Up @@ -169,6 +169,20 @@ This is the Gazebo URDF model for the Intel RealSense D455 camera
</z>
</linear_acceleration>
</imu>
<plugin name='${camera_name}_gyro_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/gyro/data_raw</remapping>
</ros>
<frame_name>${gyro_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
<plugin name='${camera_name}_accel_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/accel/data_raw</remapping>
</ros>
<frame_name>${accel_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
</sensor>
</gazebo>

Expand Down Expand Up @@ -197,20 +211,6 @@ This is the Gazebo URDF model for the Intel RealSense D455 camera
<pointCloudCutoff>0.25</pointCloudCutoff>
<pointCloudCutoffMax>9.0</pointCloudCutoffMax>
</plugin>
<plugin name='${camera_name}_gyro_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/camera/gyro/sample</remapping>
</ros>
<frame_name>${gyro_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
<plugin name='${camera_name}_accel_plugin' filename='libgazebo_ros_imu_sensor.so'>
<ros>
<remapping>~/out:=${camera_name}/camera/accel/sample</remapping>
</ros>
<frame_name>${accel_optical_frame}</frame_name>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
</gazebo>

</xacro:macro>
Expand Down

0 comments on commit 161c0fe

Please sign in to comment.