Skip to content

Conversation

m-tartari
Copy link

The D435i camera publishes IMU data on 2 different topics (/camera/accel/sample and /camera/gyro/sample) which publish from different frames (/camera_accel_optical_frame and /camera_gyro_optical_frame respectively)

  • /camera/accel/sample publishes sensor_msgs/Imu messages containing:
header: 
  seq: xxxxx
  stamp: 
    secs: xxxxx
    nsecs: xxxxx
  frame_id: /camera_accel_optical_frame
orientation: 
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
orientation_covariance: [-1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity: 
  x: 0.0
  y: 0.0
  z: 0.0
angular_velocity_covariance: [0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1]
linear_acceleration: 
  x: x.x
  y: x.x
  z: x.x
linear_acceleration_covariance: [x.x, 0.0, 0.0, 0.0, x.x, 0.0, 0.0, 0.0, x.x]
  • /camera/gyro/sample publishes sensor_msgs/Imu messages containing:
header: 
  seq: xxxxx
  stamp: 
    secs: xxxxx
    nsecs: xxxxx
  frame_id: /camera_gyro_optical_frame
orientation: 
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
orientation_covariance: [-1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity: 
  x: x.x
  y: x.x
  z: x.x
angular_velocity_covariance: [x.x, 0.0, 0.0, 0.0, x.x, 0.0, 0.0, 0.0, x.x]
linear_acceleration:
  x: 0.0
  y: 0.0
  z: 0.0
linear_acceleration_covariance: [0.1, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.1] 

I've made 2 independent gazebo plug-ins that are stripped-down versions of standard gazebo imu (gazebo_ros_imu_sensor).

I've added in README.md the instructions to use them in the xacro files.

@m-tartari
Copy link
Author

I've removed the usage section for the README.md, I've placed replaced it with the following:

" The plugins are needed for the URDF models of realsense cameras that will soon be available at pal-robotics-forks/realsense.
A working model using this plugin can currently be found at m-tartari/realsense_gazebo_description. "

It's meant to be a temporary statement (for as long as the xacro files on pal-robotics-forks/realsense are not updated). Feel free to further comment and/or request changes.

@5dollars0909
Copy link

Hello, I would like to ask if this issue has been resolved? I really need the IMU information from the camera. Thank you.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants