ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

Navsat_transform_node does not subscribe to IMU topic

asked 2018-03-30 08:24:52 -0500

antonin_haulot gravatar image

updated 2018-04-04 09:58:34 -0500

Hello,

I am currently trying to use the navsat_transform_node from the robot_localization package in a ROS-Gazebo simulation. I'm using Ubuntu 16.04 LTS, with ROS kinetic and Gazebo 7.

In order to work, this node needs to subscribe to 3 differents topics : an odometry topic with nav_msgs/Odometry message, an IMU topic with sensor_msgs/Imu and a GPS topic with sensor_msgs/NavSatFix.

My problem is that, when launching the navsat_transform_node does not subscribe to my IMU topic, even if the message type of the IMU topic published by gazebo is sensor_msgs/Imu. However, the node does subscribe to the odom and gps topics.

Here is my launch file (taken from the robot localization wiki) :

<?xml version="1.0" encoding="UTF-8"?>
<launch>
  <node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" respawn="true">
    <param name="magnetic_declination_radians" value="0"/>
    <param name="yaw_offset" value="0"/>
    <remap from="/imu/data" to="/imu_data" />
    <remap from="/gps/fix" to="/gps/fix" />
    <remap from="/odometry/filtered" to="/odom" />
  </node>
</launch>

Here is the IMU code from the URDF file of my robot model :

  <joint name="imu_joint" type="fixed">
    <axis xyz="0 0 1"/> <!-- 0 1 0 -->
    <origin xyz="${length_chassis*(5/16)} 0 ${height_chassis-(wheel_radius/2)}"/>
    <parent link="base_link"/>
    <child link="imu_link"/>
  </joint>

<link name="imu_link">
  <inertial>
    <mass value="0.001"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
  </inertial>
  <visual>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <geometry>
      <box size=" ${IMU_size} ${IMU_size} ${IMU_size}"/>
    </geometry>
    <material name="green"/>
  </visual>
  <collision>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <geometry>
      <box size="${IMU_size} ${IMU_size} ${IMU_size}"/>
    </geometry>
  </collision>
</link>

And here is the IMU plugin :

<gazebo >
    <plugin name="imu_plugin" filename="libhector_gazebo_ros_imu.so">
      <alwaysOn>true</alwaysOn>
      <bodyName>imu_link</bodyName>
      <frameId>imu_link</frameId>
      <topicName>/imu_data</topicName>
      <serviceName>imu_service</serviceName>
      <gaussianNoise>0.0</gaussianNoise>
      <updateRate>20.0</updateRate>
      <xyzOffsets>0 0 0</xyzOffsets>
      <rpyOffsets>0 0 0</rpyOffsets>
    </plugin>    
</gazebo>

When echo-ing the topic /imu_data, I get :

---
header: 
  seq: 327
  stamp: 
    secs: 16
    nsecs: 400000000
  frame_id: "imu_link"
orientation: 
  x: 4.69962116857e-06
  y: -4.8838604247e-08
  z: 7.97720664175e-05
  w: 0.999999996807
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity: 
  x: -4.49165569326e-13
  y: 6.43295283435e-15
  z: 2.52244385042e-12
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration: 
  x: 3.40118210419e-07
  y: 9.18946096526e-05
  z: 9.79999999084
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
---

Also, @Tom Moore told me to post a sample message for every sensor input, so here is the sample from the topic /odom :

---
header: 
  seq: 165673
  stamp: 
    secs: 1661
    nsecs: 260000000
  frame_id: "odom"
child_frame_id: "base_link"
pose: 
  pose: 
    position: 
      x: 0.267229286097
      y: 0.00580914153162
      z: 0.299999489939
    orientation: 
      x: 1.20893461539e-05
      y: -8.60155713043e-08
      z: 0.0124744407312
      w: 0.999922191064
  covariance: [1e-05, 0.0, 0.0, 0 ...
(more)
edit retag flag offensive close merge delete

Comments

I'm a little suspicious that it has something to do with your TFs. If you could post your TF tree (without trying to run navsat transform) that would be useful.

stevejp gravatar image stevejp  ( 2018-04-03 12:04:39 -0500 )edit

I can not post image since I do not have enough karma point to upload a file

antonin_haulot gravatar image antonin_haulot  ( 2018-04-04 04:50:30 -0500 )edit

Upload it somewhere else and post the link here.

l4ncelot gravatar image l4ncelot  ( 2018-04-04 09:31:43 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
8

answered 2018-04-09 04:03:03 -0500

Tom Moore gravatar image

A couple things:

  1. Your IMU data has a frame_id of imu_link, and your GPS has a frame_id of GPS_link. You need to define static transforms from imu_link -> base_link and from gps_link to base_link.
  2. Keep in mind that, once navsat_transform_node gets a single usable IMU message, it unsubscribes from the IMU data. It only needs a single earth-referenced heading measurement.
edit flag offensive delete link more

Comments

1

Thank you for your answer. It seems that with the correct static transforms, the node is working fine !

antonin_haulot gravatar image antonin_haulot  ( 2018-04-13 10:22:46 -0500 )edit

What is the best way to get earth referenced heading measurement from IMU?

Jimeat gravatar image Jimeat  ( 2018-07-26 18:07:29 -0500 )edit

Please ask a separate question.

Tom Moore gravatar image Tom Moore  ( 2018-08-03 03:53:00 -0500 )edit

could you please tell me how you solved this in details?, thanks in advance.

A.Mahrous gravatar image A.Mahrous  ( 2019-09-30 23:24:43 -0500 )edit

can you please show the launch file with the correct static transforms. I seem to have this exact same issue and have tried to write static transforms for both base_link -> imu_link and base_link -> gps (my GPS frame_id--from bag1) only to gain no result.

atwin gravatar image atwin  ( 2020-06-10 20:30:34 -0500 )edit
1

@Tom Moore hi, regardin the first point which you mentioned, in the tf tree i can see that gps and imu link through a number of other links are connected to the base_link. i have also checked the tf between gps_link to base_link AND imu_link -> base_link. it starts publishing. so in this case d i need to define the static transforms again??

thanks

Delbina gravatar image Delbina  ( 2022-03-22 05:28:22 -0500 )edit

Please ask a new question.

Tom Moore gravatar image Tom Moore  ( 2022-04-08 10:11:10 -0500 )edit
0

answered 2018-03-30 17:04:27 -0500

cagatayyuruk gravatar image

In your /imu/data frame_id: looks base_link, it can be problem.

Change frame_id to /imu/link.

edit flag offensive delete link more

Comments

Crazy behavior I have spent hours trying to see the /imu topic being subscribed by navsat_transform_node and nave saw it! Then quickly echoing the /imu topic in subsequent seconds, I checked this behavior:

new_nav2_ws$ ros2 topic info /imu
Type: sensor_msgs/msg/Imu
Publisher count: 0
Subscription count: 2

new_nav2_ws$ ros2 topic info /imu
Type: sensor_msgs/msg/Imu
Publisher count: 1
Subscription count: 1

the navsat_transform node consumed once the imu data and unsubscribed (the counter fall from 2 to 1)

Vini71 gravatar image Vini71  ( 2023-08-08 16:24:04 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-03-30 08:24:52 -0500

Seen: 1,585 times

Last updated: Apr 09 '18