ros2 / rmw_fastrtps

Implementation of the ROS Middleware (rmw) Interface using eProsima's Fast RTPS.
Apache License 2.0
157 stars 117 forks source link

[ros2 humble]:very large delay in transferring images with ros2 service #710

Open shuguangzhao01 opened 1 year ago

shuguangzhao01 commented 1 year ago

Bug report

Required Info:

Steps to reproduce issue

int main(int argc, char** argv) {
    rclcpp::init(argc, argv);

    std::shared_ptr<rclcpp::Node> node =
        rclcpp::Node::make_shared("udf_test_c");
    rclcpp::Client<UdfAccessSRV>::SharedPtr client =
        node->create_client<UdfAccessSRV>("udf_access_srv");
    // rclcpp::executors::MultiThreadedExecutor executor;
    long i = 1;
    std::string file =
        "/home/marco/workspace/material/video/1080050990-1-208.mp4";
    while (i < 1000000000000000) {
        cv::VideoCapture sensor(file);
        sensor.open(file);
        if (!sensor.isOpened()) {
            // RCLCPP_INFO(rclcpp::get_logger("test"),
            //             "open sensor................");
            sensor.open(file);
        }
        cv::Mat img;
        while (sensor.read(img)) {
            i += 1;
            boost::uuids::uuid a_uuid = boost::uuids::random_generator()();
            std::string uuid_string = boost::uuids::to_string(a_uuid);
            RCLCPP_INFO(rclcpp::get_logger("test"), "[%s] get a frame....i=%d", uuid_string.c_str(), i);
            if (!img.empty()) {
                RCLCPP_INFO(rclcpp::get_logger("test"), "send this image....", uuid_string.c_str());
                auto req = std::make_shared<UdfAccessSRV::Request>();

                sensor_msgs::msg::Image _img_msg;
                std_msgs::msg::Header _header;
                cv_bridge::CvImage _cv_bridge;
                _header.stamp = node->get_clock()->now();
                _cv_bridge = cv_bridge::CvImage(
                    _header, sensor_msgs::image_encodings::BGR8, img);
                _cv_bridge.toImageMsg(_img_msg);

                req->img = _img_msg;
                req->uuid = uuid_string;

                RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
                    "[%s] service_name=udf_access_srv", uuid_string.c_str());
                while (!client->wait_for_service(
                    std::chrono::milliseconds(1000))) {
                    if (!rclcpp::ok()) {
                        RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),
                            "[%s] Interrupted while waiting for the "
                            "service. Exiting.", uuid_string.c_str());
                        throw std::runtime_error("Interrupted while waiting "
                            "for the service. Exiting.");
                    }
                    RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
                        "[%s] service not available, waiting again...", uuid_string.c_str());
                }

                RCLCPP_INFO(rclcpp::get_logger("UdfInferenceService"),
                    "[%s] begin call async_send_request.......", uuid_string.c_str());
                auto result = client->async_send_request(req);
                RCLCPP_INFO(rclcpp::get_logger("UdfInferenceService"),
                    "[%s] call async_send_request finish.......", uuid_string.c_str());
                if (rclcpp::spin_until_future_complete(
                    node->get_node_base_interface(), result,
                    std::chrono::milliseconds(10000)) ==
                    rclcpp::FutureReturnCode::SUCCESS) {
                    RCLCPP_INFO(rclcpp::get_logger("UdfInferenceService"),
                        "[%s] call async_send_request finish and get a flag "
                        "of success.......", uuid_string.c_str());
                    // result_obj = result.get()->result_obj;
                    // param_obj = result.get()->param_obj;

                }
                else {
                    RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),
                        "[%s] Connet timeout!,the service "
                        "unavailable,service name=222", uuid_string.c_str());
                    throw UdfRuntimeException(
                        "Get Response timeout! the service unavailable,service "
                        "name=333");
                }

                RCLCPP_INFO(rclcpp::get_logger("test"),
                    "[%s] this frame finished................", uuid_string.c_str());
            }
            else {
                RCLCPP_ERROR(rclcpp::get_logger("test"),
                    "[%s] this capture read error................", uuid_string.c_str());
            }
            img.release();
        }
        RCLCPP_ERROR(rclcpp::get_logger("test"), "a epoch over..........");
        sensor.release();
    }
    rclcpp::shutdown();
    return 0;
}
[INFO] [1691565196.771440781] [test]: [6d415829-163b-4159-bb30-4094311212a7] get a frame....i=11393
[INFO] [1691565196.771467339] [test]: send this image....
---------3------------
[INFO] [1691565196.774480256] [rclcpp]: [6d415829-163b-4159-bb30-4094311212a7] service_name=udf_access_srv
[INFO] [1691565196.774525343] [UdfInferenceService]: [6d415829-163b-4159-bb30-4094311212a7] begin call async_send_request.......
[DEBUG] [1691565196.774541661] [rcl]: Client sending service request
[INFO] [1691565196.777880810] [UdfInferenceService]: [6d415829-163b-4159-bb30-4094311212a7] call async_send_request finish.......
[DEBUG] [1691565196.777914055] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '0' services
[DEBUG] [1691565196.783423899] [rcl]: Client taking service response
[DEBUG] [1691565196.783469595] [rcl]: Client take response succeeded: true
[INFO] [1691565196.783519505] [UdfInferenceService]: [6d415829-163b-4159-bb30-4094311212a7] call async_send_request finish and get a flag of success.......
[INFO] [1691565196.783531199] [test]: [6d415829-163b-4159-bb30-4094311212a7] this frame finished................
[INFO] [1691565196.786158914] [test]: [0688780a-a38a-483d-884d-828d82d8b0c7] get a frame....i=11394
[INFO] [1691565196.786178811] [test]: send this image....
---------3------------
[INFO] [1691565196.788508240] [rclcpp]: [0688780a-a38a-483d-884d-828d82d8b0c7] service_name=udf_access_srv
[INFO] [1691565196.788542575] [UdfInferenceService]: [0688780a-a38a-483d-884d-828d82d8b0c7] begin call async_send_request.......
[DEBUG] [1691565196.788552692] [rcl]: Client sending service request
[INFO] [1691565196.790921418] [UdfInferenceService]: [0688780a-a38a-483d-884d-828d82d8b0c7] call async_send_request finish.......
[DEBUG] [1691565196.790949868] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '0' services
[DEBUG] [1691565198.936368542] [rcl]: Client taking service response
[DEBUG] [1691565198.936401153] [rcl]: Client take response succeeded: true
[INFO] [1691565198.936432120] [UdfInferenceService]: [0688780a-a38a-483d-884d-828d82d8b0c7] call async_send_request finish and get a flag of success.......
[INFO] [1691565198.936439903] [test]: [0688780a-a38a-483d-884d-828d82d8b0c7] this frame finished................
[INFO] [1691565198.939358797] [test]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] get a frame....i=11395
[INFO] [1691565198.939399646] [test]: send this image....
---------3------------
[INFO] [1691565198.943197087] [rclcpp]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] service_name=udf_access_srv
[INFO] [1691565198.943230232] [UdfInferenceService]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] begin call async_send_request.......
[DEBUG] [1691565198.943240302] [rcl]: Client sending service request
[INFO] [1691565198.945444819] [UdfInferenceService]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] call async_send_request finish.......
[DEBUG] [1691565198.945471990] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '0' services
[DEBUG] [1691565201.931784927] [rcl]: Client taking service response
[DEBUG] [1691565201.931820007] [rcl]: Client take response succeeded: true
[INFO] [1691565201.931853762] [UdfInferenceService]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] call async_send_request finish and get a flag of success.......
[INFO] [1691565201.931862110] [test]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] this frame finished................
namespace UDF_INFERENCE_SERVER {

    UdfInferenceServer::UdfInferenceServer(const std::string& node_name,
        const rclcpp::NodeOptions& options)
        : _node_name(node_name), Node(node_name, options) {

        // create multi-thread service
        RCLCPP_INFO(this->get_logger(),
            "the main thread of the ros is starting...................");
        this->callbackGroup1_ =
            this->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
        rmw_qos_profile_t custom_qos_profile = rmw_qos_profile_default;

        // create service void
        this->udfAccessSRVPtr_ = this->create_service<UdfAccessSRV>(
            "udf_access_srv",
            std::bind(&UdfInferenceServer::udfAccessSRV_callback, this,
                std::placeholders::_1, std::placeholders::_2),
            custom_qos_profile, this->callbackGroup1_);
        RCLCPP_INFO(this->get_logger(), "UdfInferenceServer started finish...");
    }

    void UdfInferenceServer::udfAccessSRV_callback(
        const UdfAccessSRV::Request::SharedPtr request,
        const UdfAccessSRV::Response::SharedPtr response) {

        std::string uuid = request->uuid;
        RCLCPP_INFO(this->get_logger(), "[%s] receive a image", uuid.c_str());
        sensor_msgs::msg::Image img_msg = request->img;

        cv_bridge::CvImagePtr cv_ptr;
        try {
            cv_ptr = cv_bridge::toCvCopy(img_msg, img_msg.encoding);
        }
        catch (cv_bridge::Exception& e) {
            RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what());
        }
        cv::Mat mat = cv_ptr->image;
        cv::imshow("ros server test image", cv_ptr->image);
        cv::waitKey(1);
        RCLCPP_INFO(this->get_logger(),
            "[%s] ****img.width=%d,img.hight=%d,img.channel=%d", uuid.c_str(), mat.cols,
            mat.rows, mat.channels());
        mat.release();
    }
    UdfInferenceServer::~UdfInferenceServer() {}
} // namespace UDF_INFERENCE_SERVER
int main(int argc, char** argv) {
    (void)argc;
    (void)argv;
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<UDF_INFERENCE_SERVER::UdfInferenceServer>());
    rclcpp::shutdown();
    printf("hello world udf_inference_server package\n");
    return 0;
}

[DEBUG] [1691565196.768640293] [rcl]: Sending service response [DEBUG] [1691565196.778010718] [rcl]: Service server taking service request [DEBUG] [1691565196.779105101] [rcl]: Service take request succeeded: true [INFO] [1691565196.779123537] [udf_server]: [6d415829-163b-4159-bb30-4094311212a7] receive a image [INFO] [1691565196.782993242] [udf_server]: [6d415829-163b-4159-bb30-4094311212a7] img.width=1920,img.hight=1080,img.channel=3 [DEBUG] [1691565196.783044742] [rcl]: Sending service response [DEBUG] [1691565198.927586977] [rcl]: Service server taking service request [DEBUG] [1691565198.932197639] [rcl]: Service take request succeeded: true [INFO] [1691565198.932249026] [udf_server]: [0688780a-a38a-483d-884d-828d82d8b0c7] receive a image [INFO] [1691565198.935974553] [udf_server]: [0688780a-a38a-483d-884d-828d82d8b0c7] img.width=1920,img.hight=1080,img.channel=3 [DEBUG] [1691565198.936002508] [rcl]: Sending service response [DEBUG] [1691565201.926497360] [rcl]: Service server taking service request [DEBUG] [1691565201.927646480] [rcl]: Service take request succeeded: true [INFO] [1691565201.927663745] [udf_server]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] receive a image [INFO] [1691565201.931548321] [udf_server]: [262277d5-d7ed-467a-bdf8-960b9c10ff5c] img.width=1920,img.hight=1080,img.channel=3 [DEBUG] [1691565201.931582847] [rcl]: Sending service response [DEBUG] [1691565201.947481547] [rcl]: Service server taking service request [DEBUG] [1691565201.948585700] [rcl]: Service take request succeeded: true [INFO] [1691565201.948601542] [udf_server]: [903f83cb-1c7f-42c9-a98f-eb4726898ab6] receive a image [INFO] [1691565201.952043025] [udf_server]: [903f83cb-1c7f-42c9-a98f-eb4726898ab6] img.width=1920,img.hight=1080,img.channel=3 [DEBUG] [1691565201.952080348] [rcl]: Sending service response [DEBUG] [1691565201.958807461] [rcl]: Service server taking service request [DEBUG] [1691565201.959840853] [rcl]: Service take request succeeded: true [INFO] [1691565201.959858131] [udf_server]: [48c850c9-3125-4272-be22-2576a461c771] receive a image [INFO] [1691565201.963241185] [udf_server]: [48c850c9-3125-4272-be22-2576a461c771] ****img.width=1920,img.hight=1080,img.channel=3 [DEBUG] [1691565201.963260722] [rcl]: Sending service response

Expected behavior

The client uses OpenCV to read the 1920*1080 video transmission image, and the server receives the image with low latency.

Actual behavior

At first, the image transmission delay is about 15-20 milliseconds, and after about a few minutes, the receiving delay image delay becomes larger, about 1-3 seconds, as the log above shows

fujitatomoya commented 1 year ago
[DEBUG] [1691565196.788552692] [rcl]: Client sending service request
[INFO] [1691565196.790921418] [UdfInferenceService]: [0688780a-a38a-483d-884d-828d82d8b0c7] call async_send_request finish.......
[DEBUG] [1691565196.790949868] [rcl]: Initializing wait set with '0' subscriptions, '2' guard conditions, '0' timers, '0' clients, '0' services
[DEBUG] [1691565198.936368542] [rcl]: Client taking service response
[DEBUG] [1691565198.927586977] [rcl]: Service server taking service request
[DEBUG] [1691565198.932197639] [rcl]: Service take request succeeded: true
[INFO] [1691565198.932249026] [udf_server]: [0688780a-a38a-483d-884d-828d82d8b0c7] receive a image
[INFO] [1691565198.935974553] [udf_server]: [0688780a-a38a-483d-884d-828d82d8b0c7] ****img.width=1920,img.hight=1080,img.channel=3
[DEBUG] [1691565198.936002508] [rcl]: Sending service response

according to the above timestamp information, it seems that 2-3 sec delay is in the process under RMW implementation.

i have a couple of questions,

shuguangzhao01 commented 1 year ago

@fujitatomoya Thanks very much for reply

clalancette commented 1 year ago

@MiguelCompany @EduPonz Any chance you could take a look here? Thanks.