You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I have already define my own evaluateError function, but the compiler always says error: invalid cast to abstract class type ‘gtsamexamples::GPSPose2Factor’
#1957
I have already define my own evaluateError function, but the compiler always says
error: invalid cast to abstract class type ‘gtsamexamples::GPSPose2Factor’
57 | graph.add(GPSPose2Factor(Symbol('x', 2), Point2(5, 0), gpsModel));
// Add the GPS factors
// note that there is NO prior factor needed at first pose, since GPS provides
// the global positions (and rotations given more than 1 GPS measurements)
graph.add(GPSPose2Factor(Symbol('x', 1), Point2(0, 0), gpsModel));
graph.add(GPSPose2Factor(Symbol('x', 2), Point2(5, 0), gpsModel));
graph.add(GPSPose2Factor(Symbol('x', 3), Point2(10, 0), gpsModel));
but the compiler says
Scanning dependencies of target Pose2GPSExample
[ 75%] Building CXX object cpp/CMakeFiles/Pose2GPSExample.dir/examples/Pose2GPSExample.cpp.o
/home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp: In function ‘int main(int, char**)’:
/home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp:56:66: error: invalid cast to abstract class type ‘gtsamexamples::GPSPose2Factor’
56 | graph.add(GPSPose2Factor(Symbol('x', 1), Point2(0, 0), gpsModel));
| ^
In file included from /home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp:20:
/home/xyx/codeAndDemo/gtsam-examples-master/cpp/GPSPose2Factor.h:26:7: note: because the following virtual functions are pure within ‘gtsamexamples::GPSPose2Factor’:
26 | class GPSPose2Factor: public gtsam::NoiseModelFactor1gtsam::Pose2 {
| ^~~~~~~~~~~~~~
In file included from /home/xyx/codeAndDemo/gtsam-examples-master/cpp/GPSPose2Factor.h:16,
from /home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp:20:
/usr/local/include/gtsam/nonlinear/NonlinearFactor.h:640:18: note: ‘gtsam::Vector gtsam::NoiseModelFactorN::evaluateError(const ValueTypes& ..., gtsam::NoiseModelFactorN::OptionalMatrixTypeT...) const [with ValueTypes = {gtsam::Pose2}; gtsam::Vector = Eigen::Matrix<double, -1, 1>]’
640 | virtual Vector evaluateError(const ValueTypes&... x,
| ^~~~~~~~~~~~~
at last my cmakelists is:
.....
add_library(GPSPose2Factor SHARED GPSPose2Factor.cpp)
reacted with thumbs up emoji reacted with thumbs down emoji reacted with laugh emoji reacted with hooray emoji reacted with confused emoji reacted with heart emoji reacted with rocket emoji reacted with eyes emoji
-
I have already define my own evaluateError function, but the compiler always says
error: invalid cast to abstract class type ‘gtsamexamples::GPSPose2Factor’
57 | graph.add(GPSPose2Factor(Symbol('x', 2), Point2(5, 0), gpsModel));
this is my GPSPose2Factor.h
#pragma once
#include <gtsam/nonlinear/NonlinearFactor.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Vector.h>
#include <gtsam/geometry/Pose2.h>
// you can custom namespace (if needed for your project)
namespace gtsamexamples {
class GPSPose2Factor: public gtsam::NoiseModelFactor1gtsam::Pose2 {
private:
// measurement information
double mx_, my_;
public:
GPSPose2Factor(gtsam::Key poseKey, const gtsam::Point2 m, gtsam::SharedNoiseModel model);
gtsam::Vector evaluateError(const gtsam::Pose2& p, boost::optionalgtsam::Matrix& H = boost::none) const;
};
} // namespace gtsamexamples
this is GPSPose2Factor.cpp
#include "GPSPose2Factor.h"
namespace gtsamexamples {
GPSPose2Factor::GPSPose2Factor(gtsam::Key poseKey, const gtsam::Point2 m, gtsam::SharedNoiseModel model) :gtsam::NoiseModelFactor1gtsam::Pose2(model, poseKey)
{
mx_ = m.x();
my_ = m.y();
}
gtsam::Vector GPSPose2Factor::evaluateError(const gtsam::Pose2& p, boost::optionalgtsam::Matrix& H) const {
}
}
[ 25%] Building CXX object cpp/CMakeFiles/GPSPose2Factor.dir/GPSPose2Factor.cpp.o
[ 50%] Linking CXX shared library libGPSPose2Factor.so
[ 50%] Built target GPSPose2Factor
building GPSPose2Factor is already done but Pose2GPSExample.cpp cannot correctly use the GPSPose2Factor class
this is Pose2GPSExample.cpp
#include "/home/xyx/codeAndDemo/gtsam-examples-master/cpp/GPSPose2Factor.h"
#include <gtsam/geometry/Pose2.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/nonlinear/GaussNewtonOptimizer.h>
#include <gtsam/nonlinear/Marginals.h>
using namespace std;
using namespace gtsam;
using namespace gtsamexamples;
int main(int argc, char** argv) {
// Create a factor graph container
NonlinearFactorGraph graph;
// odometry measurement noise model (covariance matrix)
noiseModel::Diagonal::shared_ptr odomModel = noiseModel::Diagonal::Sigmas(Vector3(0.5, 0.5, 0.1));
// Add odometry factors
// Create odometry (Between) factors between consecutive poses
// robot makes 90 deg right turns at x3 - x5
graph.add(BetweenFactor(Symbol('x', 1), Symbol('x', 2), Pose2(5, 0, 0), odomModel));
graph.add(BetweenFactor(Symbol('x', 2), Symbol('x', 3), Pose2(5, 0, 0), odomModel));
// 2D 'GPS' measurement noise model, 2-dim
noiseModel::Diagonal::shared_ptr gpsModel = noiseModel::Diagonal::Sigmas(Vector2(1.0, 1.0));
// Add the GPS factors
// note that there is NO prior factor needed at first pose, since GPS provides
// the global positions (and rotations given more than 1 GPS measurements)
graph.add(GPSPose2Factor(Symbol('x', 1), Point2(0, 0), gpsModel));
graph.add(GPSPose2Factor(Symbol('x', 2), Point2(5, 0), gpsModel));
graph.add(GPSPose2Factor(Symbol('x', 3), Point2(10, 0), gpsModel));
// print factor graph
graph.print("\nFactor Graph:\n");
// initial varible values for the optimization
// add random noise from ground truth values
Values initials;
initials.insert(Symbol('x', 1), Pose2(0.2, -0.3, 0.2));
initials.insert(Symbol('x', 2), Pose2(5.1, 0.3, -0.1));
initials.insert(Symbol('x', 3), Pose2(9.9, -0.1, -0.2));
// print initial values
initials.print("\nInitial Values:\n");
// Use Gauss-Newton method optimizes the initial values
GaussNewtonParams parameters;
// print per iteration
parameters.setVerbosity("ERROR");
// optimize!
GaussNewtonOptimizer optimizer(graph, initials, parameters);
Values results = optimizer.optimize();
// print final values
results.print("Final Result:\n");
// Calculate marginal covariances for all poses
Marginals marginals(graph, results);
// print marginal covariances
cout << "x1 covariance:\n" << marginals.marginalCovariance(Symbol('x', 1)) << endl;
cout << "x2 covariance:\n" << marginals.marginalCovariance(Symbol('x', 2)) << endl;
cout << "x3 covariance:\n" << marginals.marginalCovariance(Symbol('x', 3)) << endl;
return 0;
}
but the compiler says
Scanning dependencies of target Pose2GPSExample
[ 75%] Building CXX object cpp/CMakeFiles/Pose2GPSExample.dir/examples/Pose2GPSExample.cpp.o
/home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp: In function ‘int main(int, char**)’:
/home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp:56:66: error: invalid cast to abstract class type ‘gtsamexamples::GPSPose2Factor’
56 | graph.add(GPSPose2Factor(Symbol('x', 1), Point2(0, 0), gpsModel));
| ^
In file included from /home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp:20:
/home/xyx/codeAndDemo/gtsam-examples-master/cpp/GPSPose2Factor.h:26:7: note: because the following virtual functions are pure within ‘gtsamexamples::GPSPose2Factor’:
26 | class GPSPose2Factor: public gtsam::NoiseModelFactor1gtsam::Pose2 {
| ^~~~~~~~~~~~~~
In file included from /home/xyx/codeAndDemo/gtsam-examples-master/cpp/GPSPose2Factor.h:16,
from /home/xyx/codeAndDemo/gtsam-examples-master/cpp/examples/Pose2GPSExample.cpp:20:
/usr/local/include/gtsam/nonlinear/NonlinearFactor.h:640:18: note: ‘gtsam::Vector gtsam::NoiseModelFactorN::evaluateError(const ValueTypes& ..., gtsam::NoiseModelFactorN::OptionalMatrixTypeT...) const [with ValueTypes = {gtsam::Pose2}; gtsam::Vector = Eigen::Matrix<double, -1, 1>]’
640 | virtual Vector evaluateError(const ValueTypes&... x,
| ^~~~~~~~~~~~~
at last my cmakelists is:
.....
add_library(GPSPose2Factor SHARED GPSPose2Factor.cpp)
include_directories(/home/xyx/codeAndDemo/gtsam-examples-master/cpp)
add_executable(Pose2GPSExample ./examples/Pose2GPSExample.cpp)
target_link_libraries(Pose2GPSExample ${Boost_LIBRARIES} gtsam GPSPose2Factor)
.....
I have no idea what the problem is, and I would greatly appreciate it if you could provide me with some reliable solutions.
Beta Was this translation helpful? Give feedback.
All reactions