aitorzip / DeepGTAV

A plugin for GTAV that transforms it into a vision-based self-driving car research environment.
GNU General Public License v3.0
1.11k stars 275 forks source link

Wrong position of points extracted from mod #69

Closed sibojia closed 7 years ago

sibojia commented 7 years ago

I defined a point on the wheels of a car represented by a offset Vector3 w.r.t. the position of the car. I try to send this point to the client and draw it on the frame, but I find a offset between the point drawn and the real position. It's shown as below: offset I'm using 3 methods to draw the point:

  1. (yellow) Use GRAPHICS::DRAW_BOX to draw the point directly in C++. This is the correct position.
  2. (blue) Send the 3d point position and camera parameters to Python client. Draw the point using camera projection.
  3. (red) Use GRAPHICS::_WORLD3D_TO_SCREEN2D to get the 2d position of the 3d point in C++ and send it to Python. Draw the point directly in Python.

The image above is captured with the car moving fast. Notice that for a stopped car, the 3 points are at the same place, all in the correct position (yellow).

Do you have any idea how this is the case? @ai-tor Thanks!

ndrplz commented 7 years ago

Just confirming that I also encountered the same issue. I often found that GRAPHICS::_WORLD3D_TO_SCREEN2D is not really precise in drawing the 3D coordinates on screen, in particular when the entity or the camera are moving fast. Haven't found a solution yet, though.

mattangus commented 7 years ago

@sibojia How are you doing the camera projection? Seems to me that ScriptHookV doesn't give you enough information to do the projection.

aitorzip commented 7 years ago

A long time ago in a galaxy far, far away Craig Quiter when working with OpenAI to integrate GTAV into Universe, came up with a piece of code that according to him correctly projects 3D to 2D screen coordinates. I have never tested it, but maybe someone interested could try it out and comment the results here (it requires Eigen):

static Point get_2d_from_3d(const int& cam_entity, const Eigen::Vector3d& vertex, const Eigen::Vector3d& cam_coords, const Eigen::Vector3d& cam_rotation, const double& cam_near_clip, const double& cam_field_of_view, const bool& draw_debug = false)
{
    // Inspired by Artur Filopowicz: Video Games for Autonomous Driving: https://github.com/arturf1/GTA5-Scripts/blob/master/Annotator.cs#L379
    static const Eigen::Vector3d WORLD_NORTH(0.0, 1.0, 0.0);
    static const Eigen::Vector3d WORLD_UP(0.0, 0.0, 1.0);
    static const Eigen::Vector3d WORLD_EAST(1.0, 0.0, 0.0);;

    auto theta = (M_PI / 180.0) * cam_rotation;

    // camera direction, at 0 rotation the camera looks down the postive Y axis 
    auto cam_dir = Utils::rotate(WORLD_NORTH, theta);
    if (draw_debug)
    {
        auto cam_dir_line_end = cam_dir + cam_coords;
        GRAPHICS::DRAW_LINE(cam_coords.x(), cam_coords.y(), cam_coords.z(), cam_dir_line_end.x(), cam_dir_line_end.y(), cam_dir_line_end.z(), 0, 255, 0, 200);
    }

    auto clip_plane_center = cam_coords + cam_near_clip * cam_dir;
    auto camera_center = -cam_near_clip * cam_dir;

    auto near_clip_height = 2 * cam_near_clip * tan(cam_field_of_view / 2. * (M_PI / 180.)); // field of view is returned vertically
    BOOST_LOG_TRIVIAL(info) << "near_clip_height " << near_clip_height;

    auto near_clip_width = near_clip_height * GRAPHICS::_GET_SCREEN_ASPECT_RATIO(false);

    const Eigen::Vector3d cam_up = rotate(WORLD_UP, theta);
    const Eigen::Vector3d cam_east = rotate(WORLD_EAST, theta);
    const Eigen::Vector3d near_clip_to_target = vertex - clip_plane_center;
    Eigen::Vector3d camera_to_target = near_clip_to_target - camera_center; // Total distance - subtracting a negative to add clip distance
    if (draw_debug)
    {
        auto cam_up_end_line = cam_up + cam_coords;
        GRAPHICS::DRAW_LINE(cam_coords.x(), cam_coords.y(), cam_coords.z(), cam_up_end_line.x(), cam_up_end_line.y(), cam_up_end_line.z(), 100, 100, 255, 200);
        auto cam_east_end_line = cam_up + cam_coords;
        GRAPHICS::DRAW_LINE(cam_coords.x(), cam_coords.y(), cam_coords.z(), cam_east_end_line.x(), cam_east_end_line.y(), cam_east_end_line.z(), 100, 100, 255, 200);
        auto del_draw = cam_coords + near_clip_to_target;
        GRAPHICS::DRAW_LINE(clip_plane_center.x(), clip_plane_center.y(), clip_plane_center.z(), del_draw.x(), del_draw.y(), del_draw.z(), 255, 255, 100, 255);
        auto viewerDistDraw = cam_coords + camera_to_target;
        GRAPHICS::DRAW_LINE(cam_coords.x(), cam_coords.y(), cam_coords.z(), viewerDistDraw.x(), viewerDistDraw.y(), viewerDistDraw.z(), 255, 100, 100, 255);
    }

    Eigen::Vector3d camera_to_target_unit_vector = camera_to_target * (1. / camera_to_target.norm()); // Unit vector in direction of plane / line intersection

    // calc distance from camera to point on the view plane by scaling the near_clip distance by 1 / cos of the angle between camera->target (camera_to_target_unit_vector) and camera->near_clip_center (cam_dir)
    double view_plan_dist = cam_near_clip / cam_dir.dot(camera_to_target_unit_vector);

    Eigen::Vector3d up3d, forward3d, right3d;
    Utils::get_direction_vectors(cam_entity, up3d, forward3d, right3d);

    Eigen::Vector3d new_origin = clip_plane_center + (near_clip_height / 2.) * cam_up - (near_clip_width / 2.) * cam_east;
    if (draw_debug)
    {
        auto top_right = new_origin + near_clip_width * right3d;
        GRAPHICS::DRAW_LINE(new_origin.x(), new_origin.y(), new_origin.z(), top_right.x(), top_right.y(), top_right.z(), 100, 255, 100, 255);

        auto bottom_right = top_right - near_clip_height * up3d;
        GRAPHICS::DRAW_LINE(bottom_right.x(), bottom_right.y(), bottom_right.z(), top_right.x(), top_right.y(), top_right.z(), 100, 255, 100, 255);

        auto bottom_left = bottom_right - near_clip_width * right3d;
        GRAPHICS::DRAW_LINE(bottom_right.x(), bottom_right.y(), bottom_right.z(), bottom_left.x(), bottom_left.y(), bottom_left.z(), 100, 255, 100, 255);

        GRAPHICS::DRAW_LINE(bottom_left.x(), bottom_left.y(), bottom_left.z(), new_origin.x(), new_origin.y(), new_origin.z(), 100, 255, 100, 255);
    }

    Point ret;
    bool use_artur_method = false;
    if ( use_artur_method )
    {
        Eigen::Vector3d view_plane_point = view_plan_dist * camera_to_target_unit_vector + camera_center;
        view_plane_point = (view_plane_point + clip_plane_center) - new_origin;
        double viewPlaneX = view_plane_point.dot(cam_east) / cam_east.dot(cam_east);
        double viewPlaneZ = view_plane_point.dot(cam_up) / cam_up.dot(cam_up);
        double screenX = viewPlaneX / near_clip_width;
        double screenY = -viewPlaneZ / near_clip_height;
        ret = { screenX, screenY };
    }
    else
    {
        auto intersection = cam_coords + view_plan_dist * camera_to_target_unit_vector;
        if (draw_debug)
        {
            draw_marker(to_shared_mem_vector(intersection), 255, 0, 0, 0.025);
        }
        auto center_to_intersection = clip_plane_center - intersection;
        auto x_dist = center_to_intersection.dot(right3d);
        auto z_dist = center_to_intersection.dot(up3d);
        auto screen_x = 1. - (near_clip_width / 2. + x_dist) / near_clip_width;
        auto screen_y = (near_clip_height / 2. + z_dist) / near_clip_height;
        ret = { screen_x, screen_y };
    }
    return ret;
}
sibojia commented 7 years ago

@mattangus x_screen = K \dot R \dot T \dot x_model (roughly like that). You can get R and T from CAM::GET_CAM_COORD and CAM::GET_CAM_ROT, and get K (intrinsic) from CAM::GET_CAM_FOV and screen resolution. Also you have to disable the post render effects as it introduces lens distortions without accessible parameters. As the points are right when the cars are stopped, I believe the method is correct.

sibojia commented 7 years ago

@ndrplz I think I found a solution. First you have to make sure that the data and the frame are at the same time point, this can be done by a scriptWait(), like:

get_data();
scriptWait(0); // To let the game render this frame
screen_capture(); 

This alone didn't solve the problem. Method 3 is incorrect and we can do nothing. After some digging I find that the bad guy with method 2 is CAM::GET_CAM_COORD, which is returning a delayed location of the camera. As the camera is attached to the car, I used the car location and the offset to calculate the location of the camera. Now method 1 and method 2 is giving the same location, as expected.

@ai-tor I didn't try the code as my projection code works well (described in my last post), and I don't know how to get near clip distance.

muaz-git commented 6 years ago

I found solution here more helpful. There are still bit lags but much much better than simply using _WORLD3D_TO_SCREEN2D. Sometimes using matrices from either previous or next frame gives more accuracy but still finding the general pattern for more accurate boxes. If anyone find better solution please let me know.