Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rainer/851 #852

Merged
merged 2 commits into from
Dec 14, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 10 additions & 8 deletions g2o/core/optimizable_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,15 +135,17 @@
for (size_t i = 0; i < _parameters.size(); i++) {
int index = _parameterIds[i];
*_parameters[i] = graph()->parameter(index);
if (!*_parameters[i]) {
G2O_CRITICAL(
"parameter {} is NULL. Check setParameterId() calls for the edge.",
i);
return false;
}
auto& aux = **_parameters[i];
if (typeid(aux).name() != _parameterTypes[i]) {
G2O_CRITICAL("parameter type mismatch - encountered {}; should be {}",
typeid(aux).name(), _parameterTypes[i]);
}
if (!*_parameters[i]) {
G2O_CRITICAL("*_parameters[i] == 0");
return false;
}
}
return true;
}
Expand Down Expand Up @@ -228,12 +230,12 @@
e->_internalId = _nextEdgeId++;
if (e->numUndefinedVertices()) return true;
if (!e->resolveParameters()) {
G2O_ERROR("{}: FATAL, cannot resolve parameters for edge {}",
G2O_ERROR("FATAL, cannot resolve parameters for edge {}",
static_cast<void*>(e));
return false;
}
if (!e->resolveCaches()) {
G2O_ERROR("{}: FATAL, cannot resolve caches for edge {}",
G2O_ERROR("FATAL, cannot resolve caches for edge {}",

Check warning on line 238 in g2o/core/optimizable_graph.cpp

View check run for this annotation

Codecov / codecov/patch

g2o/core/optimizable_graph.cpp#L238

Added line #L238 was not covered by tests
static_cast<void*>(e));
return false;
}
Expand Down Expand Up @@ -263,12 +265,12 @@
OptimizableGraph::Edge* ee = static_cast<OptimizableGraph::Edge*>(e);
#endif
if (!ee->resolveParameters()) {
G2O_ERROR("{}: FATAL, cannot resolve parameters for edge {}",
G2O_ERROR("FATAL, cannot resolve parameters for edge {}",

Check warning on line 268 in g2o/core/optimizable_graph.cpp

View check run for this annotation

Codecov / codecov/patch

g2o/core/optimizable_graph.cpp#L268

Added line #L268 was not covered by tests
static_cast<void*>(e));
return false;
}
if (!ee->resolveCaches()) {
G2O_ERROR("{}: FATAL, cannot resolve caches for edge {}",
G2O_ERROR("FATAL, cannot resolve caches for edge {}",

Check warning on line 273 in g2o/core/optimizable_graph.cpp

View check run for this annotation

Codecov / codecov/patch

g2o/core/optimizable_graph.cpp#L273

Added line #L273 was not covered by tests
static_cast<void*>(e));
return false;
}
Expand Down
26 changes: 25 additions & 1 deletion unit_test/general/graph_operations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,10 @@
#include "g2o/core/optimization_algorithm_property.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/stuff/string_tools.h"
#include "g2o/types/slam2d/types_slam2d.h"
#include "g2o/types/slam2d/types_slam2d.h" // IWYU pragma: keep
#include "g2o/types/slam3d/edge_se3_pointxyz.h"
#include "g2o/types/slam3d/vertex_pointxyz.h"
#include "g2o/types/slam3d/vertex_se3.h"

G2O_USE_TYPE_GROUP(slam2d);

Expand Down Expand Up @@ -136,6 +139,27 @@ TEST(General, GraphAddEdge) {
delete optimizer;
}

TEST(General, GraphAddEdgeNoRequiredParam) {
g2o::SparseOptimizer* optimizer = g2o::internal::createOptimizerForTests();

g2o::VertexSE3* poseVertex = new g2o::VertexSE3();
poseVertex->setId(0);
optimizer->addVertex(poseVertex);

g2o::VertexPointXYZ* pointVertex = new g2o::VertexPointXYZ();
pointVertex->setId(1);
optimizer->addVertex(pointVertex);

g2o::EdgeSE3PointXYZ* edge = new g2o::EdgeSE3PointXYZ();
edge->setVertex(0, poseVertex);
edge->setVertex(1, pointVertex);

EXPECT_FALSE(optimizer->addEdge(edge));

optimizer->clear();
delete optimizer;
}

TEST(General, GraphChangeId) {
std::unique_ptr<g2o::SparseOptimizer> optimizer(
g2o::internal::createOptimizerForTests());
Expand Down
Loading