Use ROS2 foxy and Galactic cv_bridge meet SIGSEGV

asked 2022-07-18 23:10:33 -0500

tumb1eweed gravatar image
// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/header.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "sensor_msgs/msg/compressed_image.hpp"
#include "cv_bridge/cv_bridge.h"
#include <opencv2/opencv.hpp>

using namespace std::chrono_literals;

/* This example creates a subclass of Node and uses a fancy C++11 lambda
 * function to shorten the callback syntax, at the expense of making the
 * code somewhat more difficult to understand at first glance. */

class MinimalPublisher : public rclcpp::Node
{
public:
  MinimalPublisher()
  : Node("minimal_publisher")
  {
    publisher_ = this->create_publisher<sensor_msgs::msg::Image>("image_raw", 10);
    image_compressed_publisher_ = this->create_publisher<sensor_msgs::msg::CompressedImage>("image_raw/compressed", 10);
    //input_cvimage_->image = cv::imread("./res/img/1024_768.jpeg");
    //input_cvimage_->header.frame_id = "camera_link";
    //input_cvimage_->encoding = "bgr8";

    cv_bridge::CvImagePtr cv_ptr;

    cv::Mat img(cv::Size(1920, 1080), CV_8UC3);
    cv::randu(img, cv::Scalar(0, 0, 0), cv::Scalar(255, 255, 255));

    auto msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", img).toImageMsg();
    auto compressed_img_msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", img).toCompressedImageMsg();
    auto timer_callback =
      [&]() -> void {
        this->publisher_->publish(*msg);
        this->image_compressed_publisher_->publish(*compressed_img_msg);
        RCLCPP_INFO(this->get_logger(), "Publishing ");
      };
    timer_ = this->create_wall_timer(500ms, timer_callback);
  }

private:
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;
  rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr
      image_compressed_publisher_;
  std::shared_ptr<cv_bridge::CvImage> input_cvimage_{std::make_shared<cv_bridge::CvImage>()};
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());
  rclcpp::shutdown();
  return 0;
}

as title shows, I meet SIGSEGV by using cv_bridge in ros2 foxy, gdb info shows:

0x00007fffee00fcc4 in ?? () from /opt/ros/foxy/lib/librmw_cyclonedds_cpp.so
(gdb) bt

    #0  0x00007fffee00fcc4 in ?? () from /opt/ros/foxy/lib/librmw_cyclonedds_cpp.so
    #1  0x00007fffee0084c9 in ?? () from /opt/ros/foxy/lib/librmw_cyclonedds_cpp.so
    #2  0x00007fffedffb322 in ?? () from /opt/ros/foxy/lib/librmw_cyclonedds_cpp.so
    #3  0x00007fffedf3a6b2 in dds_write_impl () from /opt/ros/foxy/lib/x86_64-linux-gnu/libddsc.so.0
    #4  0x00007fffedf3a862 in dds_write () from /opt/ros/foxy/lib/x86_64-linux-gnu/libddsc.so.0
    #5  0x00007fffedfc6434 in rmw_publish () from /opt/ros/foxy/lib/librmw_cyclonedds_cpp.so
    #6  0x00007ffff7d86116 in rcl_publish () from /opt/ros/foxy/lib/librcl.so
    #7  0x000055555556da7f in rclcpp::Publisher<sensor_msgs::msg::Image_<std::allocator<void> >, std::allocator<void> >::do_inter_process_publish(sensor_msgs::msg::Image_<std::allocator<void> > const&) ()
    #8  0x000055555556c0c0 in rclcpp::Publisher<sensor_msgs::msg::Image_<std::allocator<void> >, std::allocator<void> >::publish(sensor_msgs::msg::Image_<std::allocator<void> > const&) ()
    #9  0x000055555556a373 in MinimalPublisher::MinimalPublisher()::{lambda()#1}::operator()() const ()
    #10 0x00005555555900b2 in void rclcpp::GenericTimer<MinimalPublisher::MinimalPublisher()::{lambda()#1}, (void*)0>::execute_callback_delegate<{lambda()#1}, (MinimalPublisher::MinimalPublisher()::{lambda()#1})0>() ()
    #11 0x000055555558f129 in rclcpp::GenericTimer<MinimalPublisher::MinimalPublisher()::{lambda()#1}, (void*)0>::execute_callback() ()
    #12 0x00007ffff7ed164d in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) () from /opt/ros/foxy/lib/librclcpp.so

and I change dds to fastrtps ... (more)

edit retag flag offensive close merge delete