Replaced Vector::Constant(N,value) with VectorN::Constant(value).

release/4.3a0
Alex Hagiopol 2016-03-12 20:47:16 -05:00
parent ae19e078c7
commit 93bf31f852
4 changed files with 6 additions and 6 deletions

View File

@ -538,7 +538,7 @@ TEST(Pose3, retract_localCoordinates)
/* ************************************************************************* */
TEST(Pose3, expmap_logmap)
{
Vector d12 = Vector::Constant(6,0.1);
Vector d12 = Vector6::Constant(0.1);
Pose3 t1 = T, t2 = t1.expmap(d12);
EXPECT(assert_equal(d12, t1.logmap(t2)));
}

View File

@ -224,16 +224,16 @@ TEST(Rot3, log)
/* ************************************************************************* */
TEST(Rot3, retract_localCoordinates)
{
Vector3 d12 = Vector::Constant(3,0.1);
Vector3 d12 = Vector3::Constant(0.1);
Rot3 R2 = R.retract(d12);
EXPECT(assert_equal(d12, R.localCoordinates(R2)));
}
/* ************************************************************************* */
TEST(Rot3, expmap_logmap)
{
Vector3 d12 = Vector::Constant(3,0.1);
Vector3 d12 = Vector3::Constant(0.1);
Rot3 R2 = R.expmap(d12);
EXPECT(assert_equal(d12, R.logmap(R2)));
EXPECT(assert_equal(d12, (Vector) R.logmap(R2)));
}
/* ************************************************************************* */

View File

@ -525,7 +525,7 @@ namespace gtsam {
Diagonal(Vector::Constant(dim, sigma)),sigma_(sigma),invsigma_(1.0/sigma) {}
/* dummy constructor to allow for serialization */
Isotropic() : Diagonal(Vector::Constant(1, 1.0)),sigma_(1.0),invsigma_(1.0) {}
Isotropic() : Diagonal(Vector1::Constant(1.0)),sigma_(1.0),invsigma_(1.0) {}
public:

View File

@ -167,7 +167,7 @@ TEST( Similarity3, retract_first_order) {
//******************************************************************************
TEST(Similarity3, localCoordinates_first_order) {
Vector d12 = Vector::Constant(7, 0.1);
Vector7 d12 = Vector7::Constant(0.1);
d12(6) = 1.0;
Similarity3 t1 = T1, t2 = t1.retract(d12);
EXPECT(assert_equal(d12, t1.localCoordinates(t2)));