ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Answers:
I publish the transform /odom -> /base_link only with the information of odometry, so it doesnt have any global information. I cloud change this with the information of the imu, but actually im not interested in global positioning.
Don't do that. robot_localization
(ekf_localization_node
or ukf_localization_node
) will publish the odom->base_link transform for you.
Here my first question, where should I set the transform for the IMU, I am trying with a transform /base_link -> /imu where imu_frame is just base_link_frame but with the rotation reported from the IMU.
Just use a static transform. You don't need to constantly update the base_link->imu transform. If your IMU is really mounted at the center of your robot, just use the tf2 (or tf) static_transform_publisher
and give it a transform of all zeros.
You mis-spelled "false" in your odom0 configuration for yaw velocity. You have:
<rosparam param="odom0_config">[false, false, false,
false, false, flase,
true, true, false,
false, false, true,
false, false, false]</rosparam>
You want:
<rosparam param="odom0_config">[false, false, false,
false, false, false,
true, true, false,
false, false, true,
false, false, false]</rosparam>
2 | No.2 Revision |
Answers:
I publish the transform /odom -> /base_link only with the information of odometry, so it doesnt have any global information. I cloud change this with the information of the imu, but actually im not interested in global positioning.
Don't do that. robot_localization
(ekf_localization_node
or ukf_localization_node
) will publish the odom->base_link transform for you.
Here my first question, where should I set the transform for the IMU, I am trying with a transform /base_link -> /imu where imu_frame is just base_link_frame but with the rotation reported from the IMU.
Just use a static transform. You don't need to constantly update the base_link->imu transform. If your IMU is really mounted at the center of your robot, just use the tf2 (or tf) static_transform_publisher
and give it a transform of all zeros.
You mis-spelled "false" in your odom0 configuration for yaw velocity. yaw. You have:
<rosparam param="odom0_config">[false, false, false,
false, false, flase,
true, true, false,
false, false, true,
false, false, false]</rosparam>
You want:
<rosparam param="odom0_config">[false, false, false,
false, false, false,
true, true, false,
false, false, true,
false, false, false]</rosparam>
3 | No.3 Revision |
Answers:
I publish the transform /odom -> /base_link only with the information of odometry, so it doesnt have any global information. I cloud change this with the information of the imu, but actually im not interested in global positioning.
Don't do that. robot_localization
(ekf_localization_node
or ukf_localization_node
) will publish the odom->base_link transform for you.
Here my first question, where should I set the transform for the IMU, I am trying with a transform /base_link -> /imu where imu_frame is just base_link_frame but with the rotation reported from the IMU.
Just use a static transform. You don't need to constantly update the base_link->imu transform. If your IMU is really mounted at the center of your robot, just use the tf2 (or tf) static_transform_publisher
and give it a transform of all zeros.
You mis-spelled "false" in your odom0 configuration for yaw. You have:
<rosparam param="odom0_config">[false, false, false,
false, false, flase,
true, true, false,
false, false, true,
false, false, false]</rosparam>
You want:
<rosparam param="odom0_config">[false, false, false,
false, false, false,
true, true, false,
false, false, true,
false, false, false]</rosparam>
EDIT in response to update:
If no output is being produced, then see my comment above about turning on debug mode. Right now, I am actually suspecting an issue with the transforms. You have forward slashes in the frame_ids
in your messages, and you also put them in the configuration for ukf_localization_node
. This would normally be correct. However, robot_localization
uses tf2
, and we strip all forward slashes from the frame_ids to be compliant with it. In other words, you should do two things
frame_id
s in your messages.frame_id
s in your ukf_localization_node
launch file.By the way, if you're only fusing velocities (like you are for odom0), then you don't need to turn on relative
mode. That's only for fusing absolute position or orientation data.
4 | No.4 Revision |
Answers:
I publish the transform /odom -> /base_link only with the information of odometry, so it doesnt have any global information. I cloud change this with the information of the imu, but actually im not interested in global positioning.
Don't do that. robot_localization
(ekf_localization_node
or ukf_localization_node
) will publish the odom->base_link transform for you.
Here my first question, where should I set the transform for the IMU, I am trying with a transform /base_link -> /imu where imu_frame is just base_link_frame but with the rotation reported from the IMU.
Just use a static transform. You don't need to constantly update the base_link->imu transform. If your IMU is really mounted at the center of your robot, just use the tf2 (or tf) static_transform_publisher
and give it a transform of all zeros.
You mis-spelled "false" in your odom0 configuration for yaw. You have:
<rosparam param="odom0_config">[false, false, false,
false, false, flase,
true, true, false,
false, false, true,
false, false, false]</rosparam>
You want:
<rosparam param="odom0_config">[false, false, false,
false, false, false,
true, true, false,
false, false, true,
false, false, false]</rosparam>
EDIT in response to update:
If no output is being produced, then see my comment above about turning on debug mode. Right now, I am actually suspecting an issue with the transforms. You have forward slashes in the frame_ids
in your messages, and you also put them in the configuration for ukf_localization_node
. This would normally be correct. However, robot_localization
uses tf2
, and we strip all forward slashes from the frame_ids to be compliant with it. In other words, you should do two things
frame_id
s in your messages.frame_id
s in your ukf_localization_node
launch file.By the way, if you're only fusing velocities (like you are for odom0), then you don't need to turn on relative
mode. That's only for fusing absolute position or orientation data.
EDIT in response to update 2:
Are you sure your IMU is outputting linear accelerations correctly? See this page. For the sample IMU message you posted above, was your IMU resting flat on a table in its neutral orientation? If so, your acceleration data is wrong. It should read +9.81 m/s^2 for Z when resting flat on a surface in its neutral orientation. If you roll it +90 degrees, it should read +9.81 m/s^2 for Y. If you pitch it +90 degrees (front end down), it should read -9.81 m/s^2 for X.