How can I set home position in mavros?

Hello everyone.
How can I send home position from my fake gps module during initialization phase?
I’m currently working in SITL mode in gazebo, and I have removed the gps joint from iris model so far so good.
I also wrote a simple ros node that keeps generating simulated gps coordinate which is like this :

#include <limits>
#include <ros/ros.h>
#include <geometry_msgs/PoseStamped.h>
#include <mavros_msgs/State.h>
#include <mavros_msgs/CommandBool.h>
#include <mavros_msgs/SetMode.h>
#include <sensor_msgs/NavSatFix.h>
#include <geographic_msgs/GeoPoseStamped.h>
#include <mavros_msgs/Altitude.h>
#include <mavros_msgs/GlobalPositionTarget.h>

#define ALT 2 // fly altitude in meters

mavros_msgs::State current_state;
void state_cb(const mavros_msgs::State::ConstPtr &msg)
{
    current_state = *msg;
}

double latitude, longitude;
bool gps_received = false;

void get_global_pose(const sensor_msgs::NavSatFix::ConstPtr &msg)
{
    // vertical coord like y
    latitude = msg->latitude;
    // horizontal coord like x
    longitude = msg->longitude;
    gps_received = true;
    ROS_INFO("latitue: %.6f longitude: %.6f altitude: %.4f", latitude, longitude, msg->altitude);
}

double altitude;
void get_altitude(const mavros_msgs::Altitude::ConstPtr &msg)
{
    altitude = msg->amsl;
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "offb_node_gps_puber");
    ros::NodeHandle nh;

    // set gps
    // setpoint_position/global
    ros::Publisher pub_global_gps = nh.advertise<sensor_msgs::NavSatFix>("mavros/global_position/global", 10);
    sensor_msgs::NavSatFix gps_target;

    //the setpoint publishing rate MUST be faster than 2Hz
    ros::Rate rate(20.0);

    // wait for GPS connection
    int i = 0;
    gps_target.longitude = 20;
    while (ros::ok())
    {
        gps_target.header.stamp = ros::Time::now();
        gps_target.header.frame_id = "map";
        gps_target.header.seq = i++;
        //https://answers.ros.org/question/10310/calculate-navsatfix-covariance/
        gps_target.position_covariance_type = gps_target.COVARIANCE_TYPE_DIAGONAL_KNOWN;
        //sample covariance taken from fake gps. I either should use Unknown, or 
        //COVARIANCE_TYPE_APPROXIMATED and come up with a proper covariance, atm I have no idea!
        gps_target.position_covariance = {1, 0, 0, 0, 1, 0, 0, 0, 1};
        //status :https://wiki.ros.org/sensor_msgs/Reviews/2010-05-31%20GPS%20Proposal_API_Review
        //https://answers.ros.org/question/319109/meaning-of-status-fields-in-sensor_msgsnavsatstatus/
        //http://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/NavSatStatus.html
        /*
            # Navigation Satellite fix status for any Global Navigation Satellite System
            # Whether to output an augmented fix is determined by both the fix
            # type and the last time differential corrections were received.  A
            # fix is valid when status >= STATUS_FIX.

            int8 STATUS_NO_FIX =  -1        # unable to fix position
            int8 STATUS_FIX =      0        # unaugmented fix
            int8 STATUS_SBAS_FIX = 1        # with satellite-based augmentation
            int8 STATUS_GBAS_FIX = 2        # with ground-based augmentation

            int8 status

            # Bits defining which Global Navigation Satellite System signals were
            # used by the receiver.

            uint16 SERVICE_GPS =     1
            uint16 SERVICE_GLONASS = 2
            uint16 SERVICE_COMPASS = 4      # includes BeiDou.
            uint16 SERVICE_GALILEO = 8

            uint16 service
        */
        gps_target.status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
        gps_target.status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
        //random location
        gps_target.latitude = 20;
        gps_target.longitude = 20;
        //what about the height? should we use the local height? 
        //should we go to 2m and then set this to 2? what if we decline?
        //should we use a specific altometer ?
        gps_target.altitude = ALT;

        pub_global_gps.publish(gps_target);

        ros::spinOnce();
        rate.sleep();
    }
    return 0;
}

The problem is, when I start the simulation, at the initialization phase, it gets stuck trying to get home position:

[ INFO] [1647069881.031994618]: HP: requesting home position
[ INFO] [1647069891.031633725]: HP: requesting home position
[ERROR] [1647069891.489842169]: TM : Time jump detected. Resetting time synchroniser.
[ INFO] [1647069901.030425796]: HP: requesting home position
[ INFO] [1647069911.036741222]: HP: requesting home position
[ INFO] [1647069921.030996704]: HP: requesting home position
[ INFO] [1647069931.030818858]: HP: requesting home position
[ INFO] [1647069941.030857069]: HP: requesting home position
[ERROR] [1647069945.789897360]: TM : Time jump detected. Resetting time synchroniser.
[ INFO] [1647069951.030237748]: HP: requesting home position
[ INFO] [1647069961.030462248]: HP: requesting home position
[ INFO] [1647069971.030516927]: HP: requesting home position
[ INFO] [1647069981.030705622]: HP: requesting home position
[ INFO] [1647069991.030550798]: HP: requesting home position
[ INFO] [1647070001.043023776]: HP: requesting home position
[ INFO] [1647070011.043772037]: HP: requesting home position
[ERROR] [1647070019.989296071]: TM : Time jump detected. Resetting time synchroniser.
[ INFO] [1647070021.030486418]: HP: requesting home position
[ INFO] [1647070031.030343993]: HP: requesting home position

What should I do to fix this issue?

Side note:
As to why I’m doing this, what I’m trying to do, is to calculate GPS coordinate and instead of physical gps module, do it in software mode.

Thanks a lot in advance.

Looking at this thread to use mavros_msgs’s CommandHome service.
However I have dificulty using the service, the rosservice call also fails so I’d really appreciate any help on this.
I tried to use the service like this as I belive since there is already a request for home position, I cant use a service client, as I do not want to request anything, I want to send the response, so here I define a server for this

ros::ServiceServer server =  nh.advertiseService("mavros/cmd/set_home", request_handler);
//or
ros::ServiceServer server =  nh.advertiseService<mavros_msgs::CommandHomeRequest, mavros_msgs::CommandHomeResponse>("mavros/cmd/set_home", request_handler);

Now when it comes to the request handler, I get confused, as how to provide the required data.
based on the rosservice info /mavros/cmd/set_home output which is as follows:

Node: /mavros
URI: rosrpc://localhost:33449
Type: mavros_msgs/CommandHome
Args: current_gps yaw latitude longitude altitude

my handler should be using CommandHome type, in which case I would be having :

bool request_handler(mavros_msgs::CommandHome& cmd)
{
    auto request = cmd.request;
   auto response = cmd.response; 
   //what to do now?
    return true;
}

or have to separate arguments like this :

bool request_handler(mavros_msgs::CommandHomeRequest& request, mavros_msgs::CommandHomeResponse& response)
{
    //.?!
    return true;
}

Now, the thing is, there is nothing in response object to fill in, except a result and status attribute while
request contains all information concerning gps such s lat, lon, alt,yaw, and current_gps which is bool.

I also tried the service client like this :

ros::ServiceClient set_home_pos_client =  nh.serviceClient<mavros_msgs::CommandHome>("mavros/cmd/set_home");

    mavros_msgs::CommandHome request;
    
    request.request.altitude = 0;
    request.request.current_gps = true;
    request.request.latitude=20.0;
    request.request.longitude=20.0;
    request.request.yaw=0;

    if (set_home_pos_client.call(request))  
    {
        ROS_INFO("Request processed successfully with response: %d status: %d", request.response.result, request.response.success);
    }
    else
    {
        ROS_INFO("Request failed!");
        return 1;
    }

and got :

Request processed successfully with response: 1 status: 0

yet, I still keep getting this :

[ INFO] [1647084882.119085314]: IMU: High resolution IMU detected!
[ INFO] [1647084883.106619128]: GF: Using MISSION_ITEM_INT
[ INFO] [1647084883.106703983]: RP: Using MISSION_ITEM_INT
[ INFO] [1647084883.106789902]: WP: Using MISSION_ITEM_INT
[ INFO] [1647084883.106863086]: VER: 1.1: Capabilities         0x000000000000e4ef
[ INFO] [1647084883.106907620]: VER: 1.1: Flight software:     010d0040 (31545f85fb000000)
[ INFO] [1647084883.106973228]: VER: 1.1: Middleware software: 010d0040 (31545f85fb000000)
[ INFO] [1647084883.107100870]: VER: 1.1: OS software:         050d00ff (8660572a3c69e0e2)
[ INFO] [1647084883.107140673]: VER: 1.1: Board hardware:      00000001
[ INFO] [1647084883.107183444]: VER: 1.1: VID/PID:             0000:0000
[ INFO] [1647084883.107211555]: VER: 1.1: UID:                 4954414c44494e4f
[ WARN] [1647084883.108537423]: CMD: Unexpected command 520, result 0
[ INFO] [1647084892.104266753]: HP: requesting home position
[ INFO] [1647084897.104353469]: GF: mission received
[ INFO] [1647084897.105102390]: RP: mission received
[ INFO] [1647084897.105265952]: WP: mission received
[ INFO] [1647084902.104458881]: HP: requesting home position
[ INFO] [1647084912.104236629]: HP: requesting home position

Now how should I be sending the information?
All I want to do is, when the flight wants to start, I send a gps position for the robots home/starting position which is requested at initialization phase.
Am I even in the right track?

Update 1:
based on this issue seems I must use fake_gps plugin

Use fake_gps plugin and send local position estimation as GPS data;
now, my question is, how am I supposed to do this?
There was a link (this one) to px4_config.yaml, by which one can configure PX4 to use fake_gps, however, there is no enable/disable option, so I guess checking mocap/vision would enable or disable it.
the problem is, I dont have a mocap, and I am not going to use mocap, I have no idea how vision is used,
so what should I change, so that I can send random/arbitrary gps point simulating real gps coordinates, so the ros navigation system can use it and basically navigate the drone?

How i will ensure that my set home done in PX4 ?

I think you have to send the command to px4 FCU. You can use mavros command service - set_home using rosservice from terminal or write it from a python ros script