Fixed ros1 build
This commit is contained in:
parent
239caa2906
commit
eebb4411ce
@ -380,7 +380,7 @@ ELSEIF(CATKIN_BUILD)
|
||||
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
|
||||
## is used, also find other catkin packages
|
||||
find_package(catkin REQUIRED COMPONENTS
|
||||
cv_bridge roscpp rospy sensor_msgs std_msgs image_transport message_filters tf message_generation
|
||||
cv_bridge roscpp sensor_msgs std_msgs image_transport message_filters tf message_generation
|
||||
)
|
||||
|
||||
## Generate messages in the 'msg' folder
|
||||
@ -407,7 +407,7 @@ ELSEIF(CATKIN_BUILD)
|
||||
## CATKIN_DEPENDS: catkin_packages dependent projects also need
|
||||
## DEPENDS: system dependencies of this project that dependent projects also need
|
||||
catkin_package(
|
||||
CATKIN_DEPENDS cv_bridge roscpp rospy sensor_msgs std_msgs image_transport message_filters tf message_runtime
|
||||
CATKIN_DEPENDS cv_bridge roscpp sensor_msgs std_msgs image_transport message_filters tf message_runtime
|
||||
DEPENDS OpenCV
|
||||
)
|
||||
|
||||
|
||||
@ -208,7 +208,7 @@ void FindObjectROS::publish(const find_object::DetectionInfo & info, const Heade
|
||||
infoMsg.ids.resize(info.objDetected_.size());
|
||||
infoMsg.widths.resize(info.objDetected_.size());
|
||||
infoMsg.heights.resize(info.objDetected_.size());
|
||||
infoMsg.filePaths.resize(info.objDetected_.size());
|
||||
infoMsg.file_paths.resize(info.objDetected_.size());
|
||||
infoMsg.inliers.resize(info.objDetected_.size());
|
||||
infoMsg.outliers.resize(info.objDetected_.size());
|
||||
infoMsg.homographies.resize(info.objDetected_.size());
|
||||
@ -252,7 +252,7 @@ void FindObjectROS::publish(const find_object::DetectionInfo & info, const Heade
|
||||
infoMsg.ids[infoIndex].data = iter.key();
|
||||
infoMsg.widths[infoIndex].data = iterSizes->width();
|
||||
infoMsg.heights[infoIndex].data = iterSizes->height();
|
||||
infoMsg.filePaths[infoIndex].data = iterFilePaths.value().toStdString();
|
||||
infoMsg.file_paths[infoIndex].data = iterFilePaths.value().toStdString();
|
||||
infoMsg.inliers[infoIndex].data = iterInliers.value();
|
||||
infoMsg.outliers[infoIndex].data = iterOutliers.value();
|
||||
infoMsg.homographies[infoIndex].data.resize(9);
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user