Robotics StackExchange | Archived questions

Issues compiling node when using orocos-bfl

I'm trying to build a particle filter node to acquire the true vanish point amongst a vector of potential candidates. I'm basing my codes for the filter from the tutorials in the ROS wiki, obviously removing everything involving the ardrone fork as I'm not using it. After making sure that my codes have no references to the ardrone fork, I tried to compile the code to see if it has any kind of errors that could stop it from compiling and the catkin_make gives me this lenghty error message, which has references to errors in the codes of the orocos-bfl libraries:

In file included from /opt/ros/kinetic/include/bfl/filter/../model/../pdf/conditionalpdf.h:33:0,
                 from /opt/ros/kinetic/include/bfl/filter/../model/systemmodel.h:34,
                 from /opt/ros/kinetic/include/bfl/filter/filter.h:35,
                 from /opt/ros/kinetic/include/bfl/filter/particlefilter.h:34,
                 from /opt/ros/kinetic/include/bfl/filter/bootstrapfilter.h:35,
                 from /home/jorge/fjorge_ws/src/autonavi3at/src/partfilternode.cpp:1:
/opt/ros/kinetic/include/bfl/filter/../model/../pdf/pdf.h:47:17: error: expected identifier before numeric constant
 #define DEFAULT 0 // Default sampling method, must be valid for every PDF!!
/opt/ros/kinetic/include/bfl/filter/../model/../pdf/pdf.h:47:17: error: expected before numeric constant
                 ^
/opt/ros/kinetic/include/bfl/filter/../model/../pdf/pdf.h:47:17: error: expected } before numeric constant
/opt/ros/kinetic/include/bfl/filter/../model/../pdf/pdf.h:47:17: error: expected unqualified-id before numeric constant
In file included from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/calib3d.hpp:48:0,
                 from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/opencv.hpp:56,
                 from /home/jorge/fjorge_ws/src/autonavi3at/src/partfilternode.cpp:17:
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/features2d.hpp:1194:34: error: variable or field drawKeypoints declared void
 CV_EXPORTS_W void drawKeypoints( InputArray image, const std::vector<KeyPoint>& keypoints, InputOutputArray outImage,
                                  ^
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/features2d.hpp:1194:34: error: InputArray was not declared in this scope
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/features2d.hpp:1194:34: note: suggested alternative:
In file included from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/core.hpp:59:0,
                 from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/opencv.hpp:52,
                 from /home/jorge/fjorge_ws/src/autonavi3at/src/partfilternode.cpp:17:
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/core/mat.hpp:411:28: note:   cv::InputArray
 typedef const _InputArray& InputArray;
                            ^
In file included from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/calib3d.hpp:48:0,
                 from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/opencv.hpp:56,
                 from /home/jorge/fjorge_ws/src/autonavi3at/src/partfilternode.cpp:17:
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/features2d.hpp:1194:52: error: expected primary-expression before const
 CV_EXPORTS_W void drawKeypoints( InputArray image, const std::vector<KeyPoint>& keypoints, InputOutputArray outImage,
                                                    ^
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/features2d.hpp:1194:92: error: InputOutputArray was not declared in this scope
 CV_EXPORTS_W void drawKeypoints( InputArray image, const std::vector<KeyPoint>& keypoints, InputOutputArray outImage,
                                                                                            ^
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/features2d.hpp:1194:92: note: suggested alternative:
In file included from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/core.hpp:59:0,
                 from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/opencv.hpp:52,
                 from /home/jorge/fjorge_ws/src/autonavi3at/src/partfilternode.cpp:17:
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/core/mat.hpp:415:34: note:   cv::InputOutputArray
 typedef const _InputOutputArray& InputOutputArray;
                                  ^
In file included from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/calib3d.hpp:48:0,
                 from /opt/ros/kinetic/include/opencv-3.3.1/opencv2/opencv.hpp:56,
                 from /home/jorge/fjorge_ws/src/autonavi3at/src/partfilternode.cpp:17:
/opt/ros/kinetic/include/opencv-3.3.1/opencv2/features2d.hpp:1195:32: error: expected primary-expression before const
                                const Scalar& color=Scalar::all(-1), int flags=DrawMatchesFlags::DEFAULT );
                                ^
....
autonavi3at/CMakeFiles/partfilternode.dir/build.make:62: fallo en las instrucciones para el objetivo 'autonavi3at/CMakeFiles/partfilternode.dir/src/partfilternode.cpp.o'
make[2]: *** [autonavi3at/CMakeFiles/partfilternode.dir/src/partfilternode.cpp.o] Error 1
CMakeFiles/Makefile2:5945: fallo en las instrucciones para el objetivo 'autonavi3at/CMakeFiles/partfilternode.dir/all'
make[1]: *** [autonavi3at/CMakeFiles/partfilternode.dir/all] Error 2
Makefile:138: fallo en las instrucciones para el objetivo 'all'
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

The message references lies 1 and 17 of my node several times more, and it doesn't mention any other line. This is my CMakeLists.txt file (I'm only showing the bits pertaining the BFL libraries):

find_package(PkgConfig)
pkg_check_modules(BFL REQUIRED bfl)
message("BFL include dirs:" ${BFL_INCLUDE_DIRS})
message("BFL library dirs:" ${BFL_LIBRARY_DIRS})
include_directories(${BFL_INCLUDE_DIRS})
link_directories(${BFL_LIBRARY_DIRS})
......
add_executable(partfilternode src/partfilternode.cpp)
target_link_libraries(partfilternode ${catkin_LIBRARIES} ${OpenCV_LIBS} ${BFL_LIBRARIES})

In my particle filter node I'm also using OpenCV as I intend to publish an image of what my robot sees with the vanish point marked on it (that feature is not imlemented yet as I plan to test the filter one step at a time).

The code of the node:

#include <bfl/filter/bootstrapfilter.h>
#include <bfl/model/systemmodel.h>
#include <bfl/model/measurementmodel.h>
#include "nonlinearSystemPdf.h"
#include "nonlinearMeasurementPdf.h"
#include <iostream>
#include <cmath>
#include "rbparticlefilter.h"
#include <ros/ros.h>
#include <string>
#include <fstream>
#include <vector>
#include <autonavi3at/vpCoord.h>
#include <autonavi3at/appParam.h>
#include <autonavi3at/pointVect.h>
#include <sensor_msgs/Image.h>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>


using namespace MatrixWrapper;
using namespace BFL;
using namespace std;

class ParticleFilterNode{
    ros::NodeHandle nh_;
    ros::Subscriber im_sub;
    ros::Subscriber vect_sub;
    ros::Subscriber psub;
    ros::Publisher vp_pub;
    ros::Publisher vpim_pub;
    NonlinearSystemPdf *sys_pdf;
    SystemModel<ColumnVector> *sys_model;
    NonlinearMeasurementPdf *meas_pdf;
    MeasurementModel<ColumnVector,ColumnVector> *meas_model;
    MCPdf<ColumnVector> *prior_discr;
    RbParticleFilter *filter;
    ros::Time prevNavDataTime;
    int partnum;
    cv::Mat image;
    cv_bridge::CvImageConstPtr imbuff;

public:
ParticleFilterNode(){
im_sub = nh_.subscribe("/image_hypothesis", 1, &ParticleFilterNode::measureCallback, this);
vect_sub = nh_.subscribe("/vpcloud", 1, &ParticleFilterNode::systemCallback, this);
psub = nh_.subscribe("/autonavi3at_parameters", 1, &ParticleFilterNode::paraCallback,this);
vp_pub = nh_.advertise<autonavi3at::vpCoord>("/vanish_point",1);
vpim_pub = nh_.advertise<sensor_msgs::Image>("/image_vp",1);

sys_model = NULL;
meas_model = NULL;
filter = NULL;

}

~ParticleFilterNode(){
delete sys_model;
delete meas_model;
delete filter;
}

void CreateParticleFilter(){
    /***************************
     * NonLinear system model  *
     ***************************/

    // create gaussian
ColumnVector sys_noise_Mu(STATE_SIZE);
sys_noise_Mu(1) = MU_SYSTEM_NOISE_X;
sys_noise_Mu(2) = MU_SYSTEM_NOISE_Y;

SymmetricMatrix sys_noise_Cov(STATE_SIZE);
sys_noise_Cov = 0.0;
sys_noise_Cov(1,1) = SIGMA_SYSTEM_NOISE_X;
sys_noise_Cov(1,2) = 0.0;
sys_noise_Cov(2,1) = 0.0;
sys_noise_Cov(2,2) = SIGMA_SYSTEM_NOISE_Y;


Gaussian system_Uncertainty(sys_noise_Mu, sys_noise_Cov);

    // create the nonlinear system model
sys_pdf = new NonlinearSystemPdf(system_Uncertainty);
sys_model = new SystemModel<ColumnVector>(sys_pdf);


    /********************************
     * NonLinear Measurement model  *
     ********************************/

    // Construct the measurement noise (a scalar in this case)
ColumnVector meas_noise_Mu(MEAS_SIZE);
meas_noise_Mu(1) = MU_MEAS_NOISE;
meas_noise_Mu(2) = MU_MEAS_NOISE;
SymmetricMatrix meas_noise_Cov(MEAS_SIZE);
meas_noise_Cov(1,1) = SIGMA_MEAS_NOISE;
meas_noise_Cov(1,2) = 0.0;
meas_noise_Cov(2,1) = 0.0;
meas_noise_Cov(2,2) = SIGMA_MEAS_NOISE;

Gaussian measurement_Uncertainty(meas_noise_Mu, meas_noise_Cov);


meas_pdf = new NonlinearMeasurementPdf(measurement_Uncertainty);
meas_model = new MeasurementModel<ColumnVector,ColumnVector>(meas_pdf);

    /***************************
     * Linear prior DENSITY    *
     ***************************/
    // Continuous Gaussian prior (for Kalman filters)
ColumnVector prior_Mu(STATE_SIZE);
prior_Mu(1) = PRIOR_MU_X;
prior_Mu(2) = PRIOR_MU_Y;
SymmetricMatrix prior_Cov(STATE_SIZE);
prior_Cov(1,1) = PRIOR_COV_X;
prior_Cov(1,2) = 0.0;
prior_Cov(2,1) = 0.0;
prior_Cov(2,2) = PRIOR_COV_Y;

Gaussian prior_cont(prior_Mu,prior_Cov);

    // Discrete prior for Particle filter (using the continuous Gaussian prior)
vector<Sample<ColumnVector> > prior_samples(partnum);
prior_discr = new MCPdf<ColumnVector>(partnum,STATE_SIZE);
prior_cont.SampleFrom(prior_samples,partnum,CHOLESKY,NULL);
prior_discr->ListOfSamplesSet(prior_samples);

    /******************************
     * Construction of the Filter *
     ******************************/
filter = new RbParticleFilter (prior_discr, 0.5, partnum/4.0);
}

void paraCallback(const autonavi3at::roboParam& rparam){
partnum = (int) rparam.nparticles;
}

void measureCallback(const sensor_msgs::Image::ConstPtr& msg){
try{
        imbuff = cv_bridge::toCvCopy(msg, "mono8"); //Transforms ROS image to OpenCV image
    }
    catch(cv_bridge::Exception& e){
        ROS_ERROR("Could not convert from '%s' to 'mono8'.", msg->encoding.c_str()); //Error should the conversion fail
    }

cv::Mat mask;
std::vector<cv::Point> vpc;
cv::compare(cv::Mat(imbuff->image), 0, mask, cv::CMP_NE);
cv::findNonZero(mask, vpc);
int promx = 0, promy = 0, i;
if(vpc.size() > 1){
    for(i = 0;i < vpc.size();i++){
    promx += vpc[i].x;
    promy += vpc[i].y;
    }
    promx /= i;
    promy /= i;
}else{
    promx = vpc[0].x;
    promy = vpc[0].y;
}

ColumnVector measurement(2);
measurement(1) = promx;
measurement(2) = promy;
filter->Update(meas_model, measurement);
}

void systemCallback(const autonavi3at::pointVect& vpmsg){
std::vector<float> dij = vpmsg->points.z, xp = vpmsg->points.x, yp = vpmsg->points.y;
float a = 10000;
int pos;
for(int i = 0;i < dij.size();i++){
    if(dij[i] < a){
    pos = i;
    }
}

ColumnVector input(2);
input(1) = xp[pos];
input(2) = yp[pos];
filter->Update(sys_model,input);
}};


int main(int argc, char** argv){
    ros::init(argc, argv, "ParticleFilterNode");
    ParticleFilterNode pfNode;
    ros::spin();
    return 0;
}

Note that I changed the name of the "customparticlefilter.h" header to "rbparticlefilter.h". I don't know why I get error messages related to the libraries themselves upon starting the compilation. Is there any errors on the CMakeLists or actual code of the node?

Asked by JKaiser on 2018-09-27 00:08:52 UTC

Comments

Answers

Found the problem. Looks like OpenCV clashes with BFL. The moment I eliminated all references to OpenCV, the code compiled (after changing the CMakelists for the node to include the classes created for the filter)

Asked by JKaiser on 2018-10-04 13:27:51 UTC

Comments