Skip to content

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

@sam98uele

Description

@sam98uele

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

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions