Combines message for image and information gives "invalid initialization error"
Hello,
I am currently trying to implement a message that includes the images as well as the detected bounding boxes. The publisher works very well, but the subscriber gives me the following error message:
In file included from /usr/include/boost/function/detail/maybe_include.hpp:18:0,
from /usr/include/boost/function/detail/function_iterate.hpp:14,
from /usr/include/boost/preprocessor/iteration/detail/iter/forward1.hpp:52,
from /usr/include/boost/function.hpp:64,
from /opt/ros/kinetic/include/ros/forwards.h:40,
from /opt/ros/kinetic/include/ros/common.h:37,
from /opt/ros/kinetic/include/ros/ros.h:43,
from /home/marvin/catkin_ws/src/efr_object_detection_camera/src/template_matching.cpp:5:
/usr/include/boost/function/function_template.hpp: In instantiation of ‘static void boost::detail::function::void_function_invoker1<FunctionPtr, R, T0>::invoke(boost::detail::function::function_buffer&, T0) [with FunctionPtr = void (*)(const darknet_ros_msgs::ImageWithBoundingBoxes_<std::allocator<void> >&); R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&]’:
/usr/include/boost/function/function_template.hpp:940:38: required from ‘void boost::function1<R, T1>::assign_to(Functor) [with Functor = void (*)(const darknet_ros_msgs::ImageWithBoundingBoxes_<std::allocator<void> >&); R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&]’
/usr/include/boost/function/function_template.hpp:728:7: required from ‘boost::function1<R, T1>::function1(Functor, typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<Functor>::value>::value, int>::type) [with Functor = void (*)(const darknet_ros_msgs::ImageWithBoundingBoxes_<std::allocator<void> >&); R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<Functor>::value>::value, int>::type = int]’
/usr/include/boost/function/function_template.hpp:1077:16: required from ‘boost::function<R(T0)>::function(Functor, typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<Functor>::value>::value, int>::type) [with Functor = void (*)(const darknet_ros_msgs::ImageWithBoundingBoxes_<std::allocator<void> >&); R = void; T0 = const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&; typename boost::enable_if_c<boost::type_traits::ice_not<boost::is_integral<Functor>::value>::value, int>::type = int]’
/home/marvin/catkin_ws/src/efr_object_detection_camera/src/template_matching.cpp:55:26: required from here
/usr/include/boost/function/function_template.hpp:118:11: error: invalid initialization of reference of type ‘const darknet_ros_msgs::ImageWithBoundingBoxes_<std::allocator<void> >&’ from expression of type ‘const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >’
BOOST_FUNCTION_RETURN(f(BOOST_FUNCTION_ARGS));
^
This is the message in question:
Header header
Header image_header
BoundingBox[] bounding_boxes
sensor_msgs/Image im
And this is my subscriber:
void imageCallback(const darknet_ros_msgs::ImageWithBoundingBoxes& msg) {
cv_bridge::CvImagePtr cv_ptr;
try {
cv_ptr = cv_bridge::toCvCopy(msg.im, sensor_msgs::image_encodings::BGR8);
Mat image = cv_ptr->image;
for(size_t i = 0; i < msg.bounding_boxes.size(); i++)
{
darknet_ros_msgs::BoundingBox bBox= msg.bounding_boxes[i];
double minx = bBox.xmin;
double miny = bBox.ymin;
double maxx = bBox.xmax;
double maxy = bBox.ymax;
match(image);
}
cv::waitKey(30);
} catch (cv_bridge::Exception& e) {
ROS_ERROR("Could not convert from '%s' to 'bgr8'.",
msg.im.encoding.c_str());
}
}
int main(int argc, char **argv) {
ros::init(argc, argv, "template_matching_node");
ros::NodeHandle nh;
cv::namedWindow("view");
cv::startWindowThread();
image_transport::ImageTransport it(nh);
image_transport::Subscriber sub = it.subscribe("/darknet_ros/ImageWithBoundingBoxes", 1,
imageCallback);
ros::spin ...