Undefined reference to cv::imshow(..) when compiling pkg
Hi,
I'm using ROS MELODIC on Ubuntu 18.04, Kernel 4.18.0-25. My goal is to receive (with subscriber) a video stream thank to my D435 IntelRealSense, do a traitment and re-publish on a new topic !
I did a new package but I'm sure there is a problem with, cause I have error message when I make the package.
This is my node (ultimate.cpp) :
include <ros/ros.h>
include <image_transport/image_transport.h>
include <cv_bridge/cv_bridge.h>
include <sensor_msgs/image_encodings.h>
include <opencv2/imgproc/imgproc.hpp>
include <opencv2/highgui/highgui.hpp>
include "sensor_msgs/Range.h"
include "sensor_msgs/Image.h"
include <image_transport/image_transport.h>
include <iostream>
include <signal.h>
static const std::string OPENCV_WINDOW = "Image window";
class ImageConverter
{
ros::NodeHandle nh_;
image_transport::ImageTransport it_;
image_transport::Subscriber image_sub_;
image_transport::Publisher image_pub_;
public:
ImageConverter()
: it_(nh_)
{
// Subscrive to input video feed and publish output video feed
image_sub_ = it_.subscribe("/camera/image_raw", 1, &ImageConverter::imageCb, this);
image_pub_ = it_.advertise("/image_converter/output_video", 1);
cv::namedWindow(OPENCV_WINDOW);
}
~ImageConverter()
{
cv::destroyWindow(OPENCV_WINDOW);
}
void imageCb(const sensor_msgs::ImageConstPtr& msg)
{
cv_bridge::CvImagePtr cv_ptr;
try
{
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
// Draw an example circle on the video stream
if (cv_ptr->image.rows > 60 && cv_ptr->image.cols > 60)
cv::circle(cv_ptr->image, cv::Point(50, 50), 10, CV_RGB(255,0,0));
// Update GUI Window
cv::imshow(OPENCV_WINDOW, cv_ptr->image);
cv::waitKey(3);
// Output modified video stream
image_pub_.publish(cv_ptr->toImageMsg());
}
};
int main(int argc, char** argv)
{
ros::init(argc, argv, "image_converter");
ImageConverter ic;
ros::spin();
return 0;
}
Moreover it's node come from wiki.ros : http://wiki.ros.org/cv_bridge/Tutoria...
The CMakeList.txt :
cmake_minimum_required(VERSION 2.8.3)
project(ultimate)
find_package(catkin REQUIRED COMPONENTS
cv_bridge
image_transport
roscpp
rospy
sensor_msgs
std_msgs
)
find_package(OpenCV REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
catkin_package(
INCLUDE_DIRS include
LIBRARIES ultimate
CATKIN_DEPENDS cv_bridge image_transport roscpp rospy sensor_msgs std_msgs
# DEPENDS system_lib
)
include_directories(
#include
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)
target_link_libraries (ultimate ${catkin_LIBRARIES} ${TRANSLATE_LIB} ${GESTOOS_LIB} ${OPENNI2_LIB} ${OPENCV_LIBS} ${BOOST_LIBS} ${CURL_LIB} ${RSNSE2_LIB} ${ROYALE_LIB} -pthread -ldl)
The error message :
crabe@PRJ11:~/catkin_ws$ catkin_make --only-pkg-with-deps ultimate
Base path: /home/crabe/catkin_ws
Source space: /home/crabe/catkin_ws/src
Build space: /home/crabe/catkin_ws/build
Devel space: /home/crabe/catkin_ws/devel
Install space: /home/crabe/catkin_ws/install
Whitelisted packages: ultimate
####
#### Running command: "make cmake_check_build_system" in "/home/crabe/catkin_ws/build"
####
-- Using CATKIN_DEVEL_PREFIX: /home/crabe/catkin_ws/devel
-- Using CMAKE_PREFIX_PATH: /home/crabe/catkin_ws/devel;/opt/ros/melodic
-- This workspace overlays: /home/crabe/catkin_ws/devel;/opt/ros/melodic
-- Using PYTHON_EXECUTABLE: /usr/bin/python2
-- Using Debian Python package layout
-- Using empy: /usr/bin/empy
-- Using CATKIN_ENABLE_TESTING: False
-- catkin 0.7.20
-- BUILD_SHARED_LIBS is on
-- BUILD_SHARED_LIBS is on
-- Using CATKIN_WHITELIST_PACKAGES: ultimate
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- ~~ traversing 1 packages in topological order:
-- ~~ - ultimate
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-- +++ processing catkin package: 'ultimate'
-- ==> add_subdirectory(ultimate)
-- Configuring done
-- Generating done
-- Build files have been written to: /home/crabe/catkin_ws/build
####
#### Running command: "make -j4 -l4" in "/home/crabe/catkin_ws/build"
####
Scanning dependencies of target ultimate
[ 50%] Building CXX object ultimate/CMakeFiles/ultimate.dir/src/ultimate.cpp.o
[100%] Linking CXX executable /home/crabe/catkin_ws/devel/lib ...
+100 for not posting terminal screenshots, but could you please remove all the comments from your
CMakeLists.txt
(ie: the lines starting with#
)? They are unnecessary and take up a lot of space.I have done it, sorry, Any ideas ?
I doubt very much that
${OPENCV_LIBS}
is the correct name of the variable which contains the OpenCV libraries.As you can see here, the name of the variable containing the libraries should be
OpenCV_LIBRARIES
.I'd recommend replacing
OPENCV_LIBS
withOpenCV_LIBRARIES
and trying again.I'd also recommend to search (with regular Google) on other fora (and the general internet), as this is not a ROS-specific problem, but a generic one.
Edit: and the same goes for
BOOST_LIBS
,CURL_LIB
,TRANSLATE_LIB
, etc.There don't appear to be any
find_package(..)
statements in yourCMakeLists.txt
that are related to these variables.Where are they supposed to come from?