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

Fix/warnings #656

Merged
merged 2 commits into from
Jan 5, 2021
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
4 changes: 2 additions & 2 deletions examples/Pose3Localization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ int main(const int argc, const char* argv[]) {
auto priorModel = noiseModel::Diagonal::Variances(
(Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4).finished());
Key firstKey = 0;
for (const Values::ConstKeyValuePair& key_value : *initial) {
for (const auto key_value : *initial) {
std::cout << "Adding prior to g2o file " << std::endl;
firstKey = key_value.key;
graph->addPrior(firstKey, Pose3(), priorModel);
Expand Down Expand Up @@ -74,7 +74,7 @@ int main(const int argc, const char* argv[]) {

// Calculate and print marginal covariances for all variables
Marginals marginals(*graph, result);
for (const auto& key_value : result) {
for (const auto key_value : result) {
auto p = dynamic_cast<const GenericValue<Pose3>*>(&key_value.value);
if (!p) continue;
std::cout << marginals.marginalCovariance(key_value.key) << endl;
Expand Down
2 changes: 1 addition & 1 deletion examples/Pose3SLAMExample_changeKeys.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ int main(const int argc, const char *argv[]) {
std::cout << "Rewriting input to file: " << inputFileRewritten << std::endl;
// Additional: rewrite input with simplified keys 0,1,...
Values simpleInitial;
for(const Values::ConstKeyValuePair& key_value: *initial) {
for(const auto key_value: *initial) {
Key key;
if(add)
key = key_value.key + firstKey;
Expand Down
2 changes: 1 addition & 1 deletion examples/Pose3SLAMExample_g2o.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ int main(const int argc, const char* argv[]) {
auto priorModel = noiseModel::Diagonal::Variances(
(Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4).finished());
Key firstKey = 0;
for (const Values::ConstKeyValuePair& key_value : *initial) {
for (const auto key_value : *initial) {
std::cout << "Adding prior to g2o file " << std::endl;
firstKey = key_value.key;
graph->addPrior(firstKey, Pose3(), priorModel);
Expand Down
2 changes: 1 addition & 1 deletion examples/Pose3SLAMExample_initializePose3Chordal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ int main(const int argc, const char* argv[]) {
auto priorModel = noiseModel::Diagonal::Variances(
(Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4).finished());
Key firstKey = 0;
for (const Values::ConstKeyValuePair& key_value : *initial) {
for (const auto key_value : *initial) {
std::cout << "Adding prior to g2o file " << std::endl;
firstKey = key_value.key;
graph->addPrior(firstKey, Pose3(), priorModel);
Expand Down
2 changes: 1 addition & 1 deletion examples/Pose3SLAMExample_initializePose3Gradient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ int main(const int argc, const char* argv[]) {
auto priorModel = noiseModel::Diagonal::Variances(
(Vector(6) << 1e-6, 1e-6, 1e-6, 1e-4, 1e-4, 1e-4).finished());
Key firstKey = 0;
for (const Values::ConstKeyValuePair& key_value : *initial) {
for (const auto key_value : *initial) {
std::cout << "Adding prior to g2o file " << std::endl;
firstKey = key_value.key;
graph->addPrior(firstKey, Pose3(), priorModel);
Expand Down
2 changes: 1 addition & 1 deletion examples/SolverComparer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -559,7 +559,7 @@ void runPerturb()

// Perturb values
VectorValues noise;
for(const Values::KeyValuePair& key_val: initial)
for(const Values::KeyValuePair key_val: initial)
{
Vector noisev(key_val.value.dim());
for(Vector::Index i = 0; i < noisev.size(); ++i)
Expand Down
3 changes: 3 additions & 0 deletions gtsam/geometry/Cal3.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,9 @@ class GTSAM_EXPORT Cal3 {
*/
Cal3(double fov, int w, int h);

/// Virtual destructor
virtual ~Cal3() {}

/// @}
/// @name Advanced Constructors
/// @{
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/tests/testRot3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -825,7 +825,7 @@ TEST(Rot3, RQ_derivative) {
const auto R = Rot3::RzRyRx(xyz).matrix();
const auto num = numericalDerivative11(RQ_proxy, R);
Matrix39 calc;
RQ(R, calc).second;
auto dummy = RQ(R, calc).second;

const auto err = vec_err.second;
CHECK(assert_equal(num, calc, err));
Expand Down
4 changes: 2 additions & 2 deletions gtsam/linear/VectorValues.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ namespace gtsam {
bool VectorValues::equals(const VectorValues& x, double tol) const {
if(this->size() != x.size())
return false;
for(const auto& values: boost::combine(*this, x)) {
for(const auto values: boost::combine(*this, x)) {
if(values.get<0>().first != values.get<1>().first ||
!equal_with_abs_tol(values.get<0>().second, values.get<1>().second, tol))
return false;
Expand Down Expand Up @@ -233,7 +233,7 @@ namespace gtsam {
double result = 0.0;
typedef boost::tuple<value_type, value_type> ValuePair;
using boost::adaptors::map_values;
for(const ValuePair& values: boost::combine(*this, v)) {
for(const ValuePair values: boost::combine(*this, v)) {
assert_throw(values.get<0>().first == values.get<1>().first,
invalid_argument("VectorValues::dot called with a VectorValues of different structure"));
assert_throw(values.get<0>().second.size() == values.get<1>().second.size(),
Expand Down
2 changes: 1 addition & 1 deletion gtsam/nonlinear/NonlinearFactorGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -376,7 +376,7 @@ static Scatter scatterFromValues(const Values& values) {
scatter.reserve(values.size());

// use "natural" ordering with keys taken from the initial values
for (const auto& key_value : values) {
for (const auto key_value : values) {
scatter.add(key_value.key, key_value.value.dim());
}

Expand Down
4 changes: 2 additions & 2 deletions gtsam/nonlinear/Values-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ namespace gtsam {
/** Constructor from a Filtered view copies out all values */
template<class ValueType>
Values::Values(const Values::Filtered<ValueType>& view) {
for(const typename Filtered<ValueType>::KeyValuePair& key_value: view) {
for(const auto key_value: view) {
Key key = key_value.key;
insert(key, static_cast<const ValueType&>(key_value.value));
}
Expand All @@ -226,7 +226,7 @@ namespace gtsam {
/* ************************************************************************* */
template<class ValueType>
Values::Values(const Values::ConstFiltered<ValueType>& view) {
for(const typename ConstFiltered<ValueType>::KeyValuePair& key_value: view) {
for(const auto key_value: view) {
Key key = key_value.key;
insert(key, static_cast<const ValueType&>(key_value.value));
}
Expand Down
4 changes: 2 additions & 2 deletions gtsam/nonlinear/Values.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ namespace gtsam {
/* ************************************************************************* */
size_t Values::dim() const {
size_t result = 0;
for(const ConstKeyValuePair& key_value: *this) {
for(const auto key_value: *this) {
result += key_value.value.dim();
}
return result;
Expand All @@ -215,7 +215,7 @@ namespace gtsam {
/* ************************************************************************* */
VectorValues Values::zeroVectors() const {
VectorValues result;
for(const ConstKeyValuePair& key_value: *this)
for(const auto key_value: *this)
result.insert(key_value.key, Vector::Zero(key_value.value.dim()));
return result;
}
Expand Down
2 changes: 1 addition & 1 deletion gtsam/nonlinear/internal/LevenbergMarquardtState.h
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ struct LevenbergMarquardtState : public NonlinearOptimizerState {
noiseModelCache.resize(0);
// for each of the variables, add a prior
damped.reserve(damped.size() + values.size());
for (const auto& key_value : values) {
for (const auto key_value : values) {
const Key key = key_value.key;
const size_t dim = key_value.value.dim();
const CachedModel* item = getCachedModel(dim);
Expand Down
6 changes: 3 additions & 3 deletions gtsam/nonlinear/tests/testValues.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,7 @@ TEST(Values, filter) {
int i = 0;
Values::Filtered<Value> filtered = values.filter(boost::bind(std::greater_equal<Key>(), _1, 2));
EXPECT_LONGS_EQUAL(2, (long)filtered.size());
for(const Values::Filtered<>::KeyValuePair& key_value: filtered) {
for(const auto key_value: filtered) {
if(i == 0) {
LONGS_EQUAL(2, (long)key_value.key);
try {key_value.value.cast<Pose2>();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose2");}
Expand Down Expand Up @@ -370,7 +370,7 @@ TEST(Values, filter) {
i = 0;
Values::ConstFiltered<Pose3> pose_filtered = values.filter<Pose3>();
EXPECT_LONGS_EQUAL(2, (long)pose_filtered.size());
for(const Values::ConstFiltered<Pose3>::KeyValuePair& key_value: pose_filtered) {
for(const auto key_value: pose_filtered) {
if(i == 0) {
EXPECT_LONGS_EQUAL(1, (long)key_value.key);
EXPECT(assert_equal(pose1, key_value.value));
Expand Down Expand Up @@ -408,7 +408,7 @@ TEST(Values, Symbol_filter) {
values.insert(Symbol('y', 3), pose3);

int i = 0;
for(const Values::Filtered<Value>::KeyValuePair& key_value: values.filter(Symbol::ChrTest('y'))) {
for(const auto key_value: values.filter(Symbol::ChrTest('y'))) {
if(i == 0) {
LONGS_EQUAL(Symbol('y', 1), (long)key_value.key);
EXPECT(assert_equal(pose1, key_value.value.cast<Pose3>()));
Expand Down
4 changes: 2 additions & 2 deletions gtsam/slam/InitializePose.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ static Values computePoses(const Values& initialRot,

// Upgrade rotations to full poses
Values initialPose;
for (const auto& key_value : initialRot) {
for (const auto key_value : initialRot) {
Key key = key_value.key;
const auto& rot = initialRot.at<typename Pose::Rotation>(key);
Pose initializedPose = Pose(rot, origin);
Expand All @@ -86,7 +86,7 @@ static Values computePoses(const Values& initialRot,

// put into Values structure
Values estimate;
for (const auto& key_value : GNresult) {
for (const auto key_value : GNresult) {
Key key = key_value.key;
if (key != kAnchorKey) {
const Pose& pose = GNresult.at<Pose>(key);
Expand Down
8 changes: 4 additions & 4 deletions gtsam/slam/InitializePose3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ Values InitializePose3::computeOrientationsGradient(
// this works on the inverse rotations, according to Tron&Vidal,2011
Values inverseRot;
inverseRot.insert(initialize::kAnchorKey, Rot3());
for(const auto& key_value: givenGuess) {
for(const auto key_value: givenGuess) {
Key key = key_value.key;
const Pose3& pose = givenGuess.at<Pose3>(key);
inverseRot.insert(key, pose.rotation().inverse());
Expand All @@ -139,7 +139,7 @@ Values InitializePose3::computeOrientationsGradient(
// calculate max node degree & allocate gradient
size_t maxNodeDeg = 0;
VectorValues grad;
for(const auto& key_value: inverseRot) {
for(const auto key_value: inverseRot) {
Key key = key_value.key;
grad.insert(key,Z_3x1);
size_t currNodeDeg = (adjEdgesMap.at(key)).size();
Expand All @@ -162,7 +162,7 @@ Values InitializePose3::computeOrientationsGradient(
//////////////////////////////////////////////////////////////////////////
// compute the gradient at each node
maxGrad = 0;
for (const auto& key_value : inverseRot) {
for (const auto key_value : inverseRot) {
Key key = key_value.key;
Vector gradKey = Z_3x1;
// collect the gradient for each edge incident on key
Expand Down Expand Up @@ -203,7 +203,7 @@ Values InitializePose3::computeOrientationsGradient(
// Return correct rotations
const Rot3& Rref = inverseRot.at<Rot3>(initialize::kAnchorKey); // This will be set to the identity as so far we included no prior
Values estimateRot;
for(const auto& key_value: inverseRot) {
for(const auto key_value: inverseRot) {
Key key = key_value.key;
if (key != initialize::kAnchorKey) {
const Rot3& R = inverseRot.at<Rot3>(key);
Expand Down
2 changes: 1 addition & 1 deletion gtsam/slam/dataset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -586,7 +586,7 @@ void save2D(const NonlinearFactorGraph &graph, const Values &config,
fstream stream(filename.c_str(), fstream::out);

// save poses
for (const Values::ConstKeyValuePair key_value : config) {
for (const auto key_value : config) {
const Pose2 &pose = key_value.value.cast<Pose2>();
stream << "VERTEX2 " << key_value.key << " " << pose.x() << " " << pose.y()
<< " " << pose.theta() << endl;
Expand Down
4 changes: 2 additions & 2 deletions gtsam/slam/tests/testLago.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ TEST( Lago, largeGraphNoisy_orientations ) {
Values::shared_ptr expected;
boost::tie(gmatlab, expected) = readG2o(matlabFile);

for(const Values::KeyValuePair& key_val: *expected){
for(const auto key_val: *expected){
Key k = key_val.key;
EXPECT(assert_equal(expected->at<Pose2>(k), actual.at<Pose2>(k), 1e-5));
}
Expand All @@ -310,7 +310,7 @@ TEST( Lago, largeGraphNoisy ) {
Values::shared_ptr expected;
boost::tie(gmatlab, expected) = readG2o(matlabFile);

for(const Values::KeyValuePair& key_val: *expected){
for(const auto key_val: *expected){
Key k = key_val.key;
EXPECT(assert_equal(expected->at<Pose2>(k), actual.at<Pose2>(k), 1e-2));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -308,11 +308,11 @@ int main(int argc, char** argv) {
// And to demonstrate the fixed-lag aspect, print the keys contained in each smoother after 3.0 seconds
cout << "After 15.0 seconds, each version contains to the following keys:" << endl;
cout << " Concurrent Filter Keys: " << endl;
for(const auto& key_value: concurrentFilter.getLinearizationPoint()) {
for(const auto key_value: concurrentFilter.getLinearizationPoint()) {
cout << setprecision(5) << " Key: " << key_value.key << endl;
}
cout << " Concurrent Smoother Keys: " << endl;
for(const auto& key_value: concurrentSmoother.getLinearizationPoint()) {
for(const auto key_value: concurrentSmoother.getLinearizationPoint()) {
cout << setprecision(5) << " Key: " << key_value.key << endl;
}
cout << " Fixed-Lag Smoother Keys: " << endl;
Expand Down
4 changes: 2 additions & 2 deletions gtsam_unstable/examples/SmartRangeExample_plaza1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ int main(int argc, char** argv) {
}
}
countK = 0;
for(const Values::ConstFiltered<Point2>::KeyValuePair& it: result.filter<Point2>())
for(const auto it: result.filter<Point2>())
os2 << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t1"
<< endl;
if (smart) {
Expand All @@ -256,7 +256,7 @@ int main(int argc, char** argv) {
// Write result to file
Values result = isam.calculateEstimate();
ofstream os("rangeResult.txt");
for(const Values::ConstFiltered<Pose2>::KeyValuePair& it: result.filter<Pose2>())
for(const auto it: result.filter<Pose2>())
os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t"
<< it.value.theta() << endl;
exit(0);
Expand Down
4 changes: 2 additions & 2 deletions gtsam_unstable/examples/SmartRangeExample_plaza2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,11 +202,11 @@ int main(int argc, char** argv) {
// Write result to file
Values result = isam.calculateEstimate();
ofstream os2("rangeResultLM.txt");
for(const Values::ConstFiltered<Point2>::KeyValuePair& it: result.filter<Point2>())
for(const auto it: result.filter<Point2>())
os2 << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t1"
<< endl;
ofstream os("rangeResult.txt");
for(const Values::ConstFiltered<Pose2>::KeyValuePair& it: result.filter<Pose2>())
for(const auto it: result.filter<Pose2>())
os << it.key << "\t" << it.value.x() << "\t" << it.value.y() << "\t"
<< it.value.theta() << endl;
exit(0);
Expand Down
4 changes: 2 additions & 2 deletions gtsam_unstable/nonlinear/BatchFixedLagSmoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ FixedLagSmoother::Result BatchFixedLagSmoother::update(
// Add the new variables to theta
theta_.insert(newTheta);
// Add new variables to the end of the ordering
for (const auto& key_value : newTheta) {
for (const auto key_value : newTheta) {
ordering_.push_back(key_value.key);
}
// Augment Delta
Expand Down Expand Up @@ -267,7 +267,7 @@ FixedLagSmoother::Result BatchFixedLagSmoother::optimize() {
// Put the linearization points and deltas back for specific variables
if (enforceConsistency_ && (linearKeys_.size() > 0)) {
theta_.update(linearKeys_);
for(const auto& key_value: linearKeys_) {
for(const auto key_value: linearKeys_) {
delta_.at(key_value.key) = newDelta.at(key_value.key);
}
}
Expand Down
10 changes: 5 additions & 5 deletions gtsam_unstable/nonlinear/ConcurrentBatchFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ ConcurrentBatchFilter::Result ConcurrentBatchFilter::update(const NonlinearFacto
// Add the new variables to theta
theta_.insert(newTheta);
// Add new variables to the end of the ordering
for(const Values::ConstKeyValuePair& key_value: newTheta) {
for(const auto key_value: newTheta) {
ordering_.push_back(key_value.key);
}
// Augment Delta
Expand Down Expand Up @@ -222,7 +222,7 @@ void ConcurrentBatchFilter::synchronize(const NonlinearFactorGraph& smootherSumm

// Find the set of new separator keys
KeySet newSeparatorKeys;
for(const Values::ConstKeyValuePair& key_value: separatorValues_) {
for(const auto key_value: separatorValues_) {
newSeparatorKeys.insert(key_value.key);
}

Expand All @@ -236,7 +236,7 @@ void ConcurrentBatchFilter::synchronize(const NonlinearFactorGraph& smootherSumm
graph.push_back(smootherShortcut_);
Values values;
values.insert(smootherSummarizationValues);
for(const Values::ConstKeyValuePair& key_value: separatorValues_) {
for(const auto key_value: separatorValues_) {
if(!values.exists(key_value.key)) {
values.insert(key_value.key, key_value.value);
}
Expand Down Expand Up @@ -471,7 +471,7 @@ void ConcurrentBatchFilter::optimize(const NonlinearFactorGraph& factors, Values
// Put the linearization points and deltas back for specific variables
if(linearValues.size() > 0) {
theta.update(linearValues);
for(const Values::ConstKeyValuePair& key_value: linearValues) {
for(const auto key_value: linearValues) {
delta.at(key_value.key) = newDelta.at(key_value.key);
}
}
Expand Down Expand Up @@ -574,7 +574,7 @@ void ConcurrentBatchFilter::moveSeparator(const FastList<Key>& keysToMove) {

// Calculate the set of new separator keys: AffectedKeys + PreviousSeparatorKeys - KeysToMove
KeySet newSeparatorKeys = removedFactors.keys();
for(const Values::ConstKeyValuePair& key_value: separatorValues_) {
for(const auto key_value: separatorValues_) {
newSeparatorKeys.insert(key_value.key);
}
for(Key key: keysToMove) {
Expand Down
Loading