mavros icon indicating copy to clipboard operation
mavros copied to clipboard

Topic `global_position/local` not consistent linear z velocity in ENU frame

Open sam98uele opened this issue 4 months ago • 2 comments

When filling mavros topic global_position/local and converting the linear velocity frame from NED to ENU the z coordinate is not consistent with the transformation, in fact, it remains positive toward down.

https://github.com/mavlink/mavros/blob/ros2/mavros/src/plugins/global_position.cpp#L343

    // Linear velocity
    tf2::toMsg(
      Eigen::Vector3d(gpos.vy, gpos.vx, gpos.vz) / 1E2,
      odom.twist.twist.linear);

to be consistent it should be:

    // Linear velocity
    tf2::toMsg(
      Eigen::Vector3d(gpos.vy, gpos.vx, -gpos.vz) / 1E2,
      odom.twist.twist.linear);

You can see it also from this plot:

Image

sam98uele avatar Aug 25 '25 15:08 sam98uele

Hi, is global_position/local just the ECEF coordinates reported by GPS? or is it GPS fused with other sensors?

elgarbe avatar Oct 15 '25 14:10 elgarbe

global_position/local comes from Mavlink message: GLOBAL_POSITION_INT, which (from the documentation here) it is the GPS fused with the accelerometers.

From the documentation you will also see the input reference frame of the velocity.

sam98uele avatar Oct 23 '25 16:10 sam98uele