ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You are visualizing the wrong topic for the "local" data. Here's what I see when I visualize /odometry/filtered/local
(green), /odometry/filtered/global
(red), and /odometry/gps
(blue):
rviz
fixed_frame
== map:
rviz
fixed_frame
== odom:
Both of those look completely correct to me. Your GPS is a bit noisy, but that's normal.
2 | No.2 Revision |
You are visualizing the wrong topic for the "local" data. Here's what I see when I visualize /odometry/filtered/local
(green), /odometry/filtered/global
(red), and /odometry/gps
(blue):
rviz
fixed_frame
== map:
rviz
fixed_frame
== odom:
Both of those look completely correct to me. Your GPS is a bit noisy, but that's normal.
EDIT in response to comments:
From the wiki:
Visualization of raw GPS tracks:
3 | No.3 Revision |
You are visualizing the wrong topic for the "local" data. Here's what I see when I visualize /odometry/filtered/local
(green), /odometry/filtered/global
(red), and /odometry/gps
(blue):
rviz
fixed_frame
== map:
rviz
fixed_frame
== odom:
Both of those look completely correct to me. Your GPS is a bit noisy, but that's normal.
EDIT in response to comments:
From the wiki:
Visualization of raw GPS tracks:
EDIT 2 after more analysis:
I figured out why it's so much more jittery. You need to get rid of the 0.4
value in your bl_gps
static transform:
<node pkg="tf2_ros" type="static_transform_publisher" name="bl_gps" args="0 0 0.0 0 0 0 base_link gps" />
That's a bug; I'll file a ticket. Thanks for the report!
Even with that fix, though, the direction of travel doesn't quite match the GPS. The robot has a tiny bit of lateral motion, which suggests something is not right with your IMU heading or the declination parameter.
4 | No.4 Revision |
You are visualizing the wrong topic for the "local" data. Here's what I see when I visualize /odometry/filtered/local
(green), /odometry/filtered/global
(red), and /odometry/gps
(blue):
rviz
fixed_frame
== map:
rviz
fixed_frame
== odom:
Both of those look completely correct to me. Your GPS is a bit noisy, but that's normal.
EDIT in response to comments:
From the wiki:
Visualization of raw GPS tracks:
EDIT 2 after more analysis:
I figured out why it's so much more jittery. You need to get rid of the 0.4
value for Z
in your bl_gps
static transform:
<node pkg="tf2_ros" type="static_transform_publisher" name="bl_gps" args="0 0 0.0 0 0 0 base_link gps" />
That's a bug; I'll file a ticket. Thanks for the report!
Even with that fix, though, the direction of travel doesn't quite match the GPS. The robot has a tiny bit of lateral motion, which suggests something is not right with your IMU heading or the declination parameter.
5 | No.5 Revision |
You are visualizing the wrong topic for the "local" data. Here's what I see when I visualize /odometry/filtered/local
(green), /odometry/filtered/global
(red), and /odometry/gps
(blue):
rviz
fixed_frame
== map:
rviz
fixed_frame
== odom:
Both of those look completely correct to me. Your GPS is a bit noisy, but that's normal.
EDIT in response to comments:
From the wiki:
Visualization of raw GPS tracks:
EDIT 2 after more analysis:
I figured out why it's so much more jittery. You need to get rid of the 0.4
value for Z
in your bl_gps
static transform:
<node pkg="tf2_ros" type="static_transform_publisher" name="bl_gps" args="0 0 0.0 0 0 0 base_link gps" />
That's a bug; I'll file a ticket. Thanks for the report!
Even with that fix, though, the direction of travel doesn't quite match the GPS. The robot has a tiny bit of lateral motion, which suggests something is not right with your IMU heading or the declination parameter.
EDIT 3 to answer more questions:
So you're saying the path is more accurate/in line with the GPS readings when you use the negative declination value (-0.0684)? If so, yes, that makes sense, and it's what I suggested in the comments. Your deviation from "true north" is 0.0684 radians clockwise:
Clockwise rotation in an ENU frame is negative, hence the -0.0684 declination value. I realize r_l
uses different standards than geographic services, but it's just so that the nodes handle rotations consistently.