Skip to content

Commit 90daa71

Browse files
committed
Fix stringop-overread compile issues
1 parent 0476592 commit 90daa71

File tree

6 files changed

+108
-101
lines changed

6 files changed

+108
-101
lines changed

fuse_constraints/include/fuse_constraints/normal_delta_orientation_3d_cost_functor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ class NormalDeltaOrientation3DCostFunctor
120120

121121
// Scale the residuals by the square root information matrix to account for the measurement
122122
// uncertainty.
123-
Eigen::Map<Eigen::Matrix<T, Eigen::Dynamic, 1>> residuals_map(residuals, A_.rows());
123+
Eigen::Map<Eigen::Matrix<T, 3, 1>> residuals_map(residuals);
124124
residuals_map.applyOnTheLeft(A_.template cast<T>());
125125

126126
return true;

fuse_constraints/test/test_absolute_constraint.cpp

Lines changed: 30 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -59,9 +59,9 @@ TEST(AbsoluteConstraint, Constructor)
5959
{
6060
fuse_variables::AccelerationAngular2DStamped variable(
6161
rclcpp::Time(1234, 5678), fuse_core::uuid::generate("robby"));
62-
fuse_core::Vector1d mean;
62+
fuse_core::VectorXd mean(1);
6363
mean << 3.0;
64-
fuse_core::Matrix1d cov;
64+
fuse_core::MatrixXd cov(1, 1);
6565
cov << 1.0;
6666
EXPECT_NO_THROW(
6767
fuse_constraints::AbsoluteAccelerationAngular2DStampedConstraint constraint(
@@ -70,9 +70,9 @@ TEST(AbsoluteConstraint, Constructor)
7070
{
7171
fuse_variables::AccelerationLinear2DStamped variable(rclcpp::Time(1234, 5678),
7272
fuse_core::uuid::generate("bender"));
73-
fuse_core::Vector2d mean;
73+
fuse_core::VectorXd mean(2);
7474
mean << 1.0, 2.0;
75-
fuse_core::Matrix2d cov;
75+
fuse_core::MatrixXd cov(2, 2);
7676
cov << 1.0, 0.1, 0.1, 2.0;
7777
EXPECT_NO_THROW(
7878
fuse_constraints::AbsoluteAccelerationLinear2DStampedConstraint constraint(
@@ -81,9 +81,9 @@ TEST(AbsoluteConstraint, Constructor)
8181
{
8282
fuse_variables::Orientation2DStamped variable(rclcpp::Time(1234, 5678),
8383
fuse_core::uuid::generate("johnny5"));
84-
fuse_core::Vector1d mean;
84+
fuse_core::VectorXd mean(1);
8585
mean << 3.0;
86-
fuse_core::Matrix1d cov;
86+
fuse_core::MatrixXd cov(1, 1);
8787
cov << 1.0;
8888
EXPECT_NO_THROW(
8989
fuse_constraints::AbsoluteOrientation2DStampedConstraint constraint(
@@ -92,9 +92,9 @@ TEST(AbsoluteConstraint, Constructor)
9292
{
9393
fuse_variables::Position2DStamped variable(rclcpp::Time(1234, 5678),
9494
fuse_core::uuid::generate("rosie"));
95-
fuse_core::Vector2d mean;
95+
fuse_core::VectorXd mean(2);
9696
mean << 1.0, 2.0;
97-
fuse_core::Matrix2d cov;
97+
fuse_core::MatrixXd cov(2, 2);
9898
cov << 1.0, 0.1, 0.1, 2.0;
9999
EXPECT_NO_THROW(
100100
fuse_constraints::AbsolutePosition2DStampedConstraint constraint(
@@ -103,9 +103,9 @@ TEST(AbsoluteConstraint, Constructor)
103103
{
104104
fuse_variables::Position3DStamped variable(rclcpp::Time(1234, 5678),
105105
fuse_core::uuid::generate("clank"));
106-
fuse_core::Vector3d mean;
106+
fuse_core::VectorXd mean(3);
107107
mean << 1.0, 2.0, 3.0;
108-
fuse_core::Matrix3d cov;
108+
fuse_core::MatrixXd cov(3, 3);
109109
cov << 1.0, 0.1, 0.2, 0.1, 2.0, 0.3, 0.2, 0.3, 3.0;
110110
EXPECT_NO_THROW(
111111
fuse_constraints::AbsolutePosition3DStampedConstraint constraint(
@@ -114,9 +114,9 @@ TEST(AbsoluteConstraint, Constructor)
114114
{
115115
fuse_variables::VelocityAngular2DStamped variable(rclcpp::Time(1234, 5678),
116116
fuse_core::uuid::generate("gort"));
117-
fuse_core::Vector1d mean;
117+
fuse_core::VectorXd mean(1);
118118
mean << 3.0;
119-
fuse_core::Matrix1d cov;
119+
fuse_core::MatrixXd cov(1, 1);
120120
cov << 1.0;
121121
EXPECT_NO_THROW(
122122
fuse_constraints::AbsoluteVelocityAngular2DStampedConstraint constraint(
@@ -125,9 +125,9 @@ TEST(AbsoluteConstraint, Constructor)
125125
{
126126
fuse_variables::VelocityLinear2DStamped variable(rclcpp::Time(1234, 5678),
127127
fuse_core::uuid::generate("bishop"));
128-
fuse_core::Vector2d mean;
128+
fuse_core::VectorXd mean(2);
129129
mean << 1.0, 2.0;
130-
fuse_core::Matrix2d cov;
130+
fuse_core::MatrixXd cov(2, 2);
131131
cov << 1.0, 0.1, 0.1, 2.0;
132132
EXPECT_NO_THROW(
133133
fuse_constraints::AbsoluteVelocityLinear2DStampedConstraint constraint(
@@ -140,9 +140,9 @@ TEST(AbsoluteConstraint, PartialMeasurement)
140140
{
141141
fuse_variables::Position3DStamped variable(rclcpp::Time(1234, 5678),
142142
fuse_core::uuid::generate("vici"));
143-
fuse_core::Vector2d mean;
143+
fuse_core::VectorXd mean(2);
144144
mean << 3.0, 1.0;
145-
fuse_core::Matrix2d cov;
145+
fuse_core::MatrixXd cov(2, 2);
146146
cov << 3.0, 0.2, 0.2, 1.0;
147147
auto indices = std::vector<size_t>{2, 0};
148148
EXPECT_NO_THROW(
@@ -157,9 +157,9 @@ TEST(AbsoluteConstraint, Covariance)
157157
// Verify the covariance <--> sqrt information conversions are correct
158158
fuse_variables::AccelerationLinear2DStamped variable(rclcpp::Time(1234, 5678),
159159
fuse_core::uuid::generate("chappie"));
160-
fuse_core::Vector2d mean;
160+
fuse_core::VectorXd mean(2);
161161
mean << 1.0, 2.0;
162-
fuse_core::Matrix2d cov;
162+
fuse_core::MatrixXd cov(2, 2);
163163
cov << 1.0, 0.1, 0.1, 2.0;
164164
fuse_constraints::AbsoluteAccelerationLinear2DStampedConstraint constraint("test", variable,
165165
mean, cov);
@@ -178,9 +178,9 @@ TEST(AbsoluteConstraint, Covariance)
178178
{
179179
fuse_variables::Position3DStamped variable(rclcpp::Time(1234, 5678),
180180
fuse_core::uuid::generate("astroboy"));
181-
fuse_core::Vector2d mean;
181+
fuse_core::VectorXd mean(2);
182182
mean << 3.0, 1.0;
183-
fuse_core::Matrix2d cov;
183+
fuse_core::MatrixXd cov(2, 2);
184184
cov << 3.0, 0.2, 0.2, 1.0;
185185
auto indices = std::vector<size_t>{2, 0};
186186
fuse_constraints::AbsolutePosition3DStampedConstraint constraint("test", variable, mean, cov,
@@ -214,9 +214,9 @@ TEST(AbsoluteConstraint, Optimization)
214214
variable->x() = 10.7;
215215
variable->y() = -3.2;
216216
// Create an absolute constraint
217-
fuse_core::Vector2d mean;
217+
fuse_core::VectorXd mean(2);
218218
mean << 1.0, 2.0;
219-
fuse_core::Matrix2d cov;
219+
fuse_core::MatrixXd cov(2, 2);
220220
cov << 1.0, 0.1, 0.1, 2.0;
221221
auto constraint = fuse_constraints::AbsoluteAccelerationLinear2DStampedConstraint::make_shared(
222222
"test",
@@ -354,9 +354,9 @@ TEST(AbsoluteConstraint, PartialOptimization)
354354
var->z() = 0.9;
355355

356356
// Create a partial constraint for the first and third indices
357-
fuse_core::Vector2d mean1;
357+
fuse_core::VectorXd mean1(2);
358358
mean1 << 1.0, 3.0;
359-
fuse_core::Matrix2d cov1;
359+
fuse_core::MatrixXd cov1(2, 2);
360360
/* *INDENT-OFF* */
361361
cov1 << 1.0, 0.0,
362362
0.0, 1.0;
@@ -367,9 +367,9 @@ TEST(AbsoluteConstraint, PartialOptimization)
367367
"test", *var, mean1, cov1, indices1);
368368

369369
// Create another constraint for the second index
370-
fuse_core::Vector1d mean2;
370+
fuse_core::VectorXd mean2(1);
371371
mean2 << 2.0;
372-
fuse_core::Matrix1d cov2;
372+
fuse_core::MatrixXd cov2(1, 1);
373373
cov2 << 1.0;
374374
std::vector<size_t> indices2 = {fuse_variables::Position3DStamped::Y};
375375
auto constraint2 = fuse_constraints::AbsolutePosition3DStampedConstraint::make_shared(
@@ -416,9 +416,9 @@ TEST(AbsoluteConstraint, AbsoluteOrientation2DOptimization)
416416
fuse_core::uuid::generate("tiktok"));
417417
variable->yaw() = 0.7;
418418
// Create an absolute constraint
419-
fuse_core::Vector1d mean;
419+
fuse_core::VectorXd mean(1);
420420
mean << 7.0;
421-
fuse_core::Matrix1d cov;
421+
fuse_core::MatrixXd cov(1, 1);
422422
cov << 0.10;
423423
auto constraint = fuse_constraints::AbsoluteOrientation2DStampedConstraint::make_shared(
424424
"test", *variable, mean, cov);
@@ -463,9 +463,9 @@ TEST(AbsoluteConstraint, Serialization)
463463
// Construct a constraint
464464
fuse_variables::AccelerationAngular2DStamped variable(rclcpp::Time(1234, 5678),
465465
fuse_core::uuid::generate("robby"));
466-
fuse_core::Vector1d mean;
466+
fuse_core::VectorXd mean(1);
467467
mean << 3.0;
468-
fuse_core::Matrix1d cov;
468+
fuse_core::MatrixXd cov(1, 1);
469469
cov << 1.0;
470470
fuse_constraints::AbsoluteAccelerationAngular2DStampedConstraint expected("test", variable, mean,
471471
cov);

fuse_constraints/test/test_absolute_orientation_2d_stamped_constraint.cpp

Lines changed: 12 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -58,9 +58,9 @@ TEST(AbsoluteOrientation2DStampedConstraint, Constructor)
5858
// Construct a constraint just to make sure it compiles.
5959
Orientation2DStamped orientation_variable(rclcpp::Time(1234, 5678),
6060
fuse_core::uuid::generate("walle"));
61-
fuse_core::Vector1d mean;
61+
fuse_core::VectorXd mean(1);
6262
mean << 1.0;
63-
fuse_core::Matrix1d cov;
63+
fuse_core::MatrixXd cov(1, 1);
6464
cov << 1.0;
6565
EXPECT_NO_THROW(
6666
AbsoluteOrientation2DStampedConstraint constraint(
@@ -73,9 +73,9 @@ TEST(AbsoluteOrientation2DStampedConstraint, Covariance)
7373
// Verify the covariance <--> sqrt information conversions are correct
7474
Orientation2DStamped orientation_variable(rclcpp::Time(1234, 5678), fuse_core::uuid::generate(
7575
"mo"));
76-
fuse_core::Vector1d mean;
76+
fuse_core::VectorXd mean(1);
7777
mean << 1.0;
78-
fuse_core::Matrix1d cov;
78+
fuse_core::MatrixXd cov(1, 1);
7979
cov << 1.0;
8080
AbsoluteOrientation2DStampedConstraint constraint("test", orientation_variable, mean, cov);
8181

@@ -99,10 +99,9 @@ TEST(AbsoluteOrientation2DStampedConstraint, Optimization)
9999
orientation_variable->yaw() = 1.0;
100100

101101
// Create an absolute orientation constraint
102-
fuse_core::Vector1d mean;
102+
fuse_core::VectorXd mean(1);
103103
mean << 1.0;
104-
105-
fuse_core::Matrix1d cov;
104+
fuse_core::MatrixXd cov(1, 1);
106105
cov << 1.0;
107106
auto constraint = AbsoluteOrientation2DStampedConstraint::make_shared(
108107
"test",
@@ -168,10 +167,9 @@ TEST(AbsoluteOrientation2DStampedConstraint, OptimizationZero)
168167
orientation_variable->yaw() = 0.0;
169168

170169
// Create an absolute orientation constraint
171-
fuse_core::Vector1d mean;
170+
fuse_core::VectorXd mean(1);
172171
mean << 0.0;
173-
174-
fuse_core::Matrix1d cov;
172+
fuse_core::MatrixXd cov(1, 1);
175173
cov << 1.0;
176174
auto constraint = AbsoluteOrientation2DStampedConstraint::make_shared(
177175
"test",
@@ -308,10 +306,9 @@ TEST(AbsoluteOrientation2DStampedConstraint, OptimizationNegativePi)
308306
orientation_variable->yaw() = -M_PI;
309307

310308
// Create an absolute orientation constraint
311-
fuse_core::Vector1d mean;
309+
fuse_core::VectorXd mean(1);
312310
mean << -M_PI;
313-
314-
fuse_core::Matrix1d cov;
311+
fuse_core::MatrixXd cov(1, 1);
315312
cov << 1.0;
316313
auto constraint = AbsoluteOrientation2DStampedConstraint::make_shared(
317314
"test",
@@ -370,9 +367,9 @@ TEST(AbsoluteOrientation2DStampedConstraint, Serialization)
370367
// Construct a constraint
371368
Orientation2DStamped orientation_variable(rclcpp::Time(1234, 5678),
372369
fuse_core::uuid::generate("walle"));
373-
fuse_core::Vector1d mean;
370+
fuse_core::VectorXd mean(1);
374371
mean << 1.0;
375-
fuse_core::Matrix1d cov;
372+
fuse_core::MatrixXd cov(1, 1);
376373
cov << 1.0;
377374
AbsoluteOrientation2DStampedConstraint expected("test", orientation_variable, mean, cov);
378375

0 commit comments

Comments
 (0)