Skip to content

Commit

Permalink
improve syntax
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal committed Oct 22, 2024
1 parent a53290b commit 8238df2
Show file tree
Hide file tree
Showing 6 changed files with 12 additions and 24 deletions.
12 changes: 4 additions & 8 deletions tests/testPoseFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,7 @@ TEST(PoseFactor, error) {
Pose3 cMp = Pose3(Rot3(), Point3(-2, 0, 0));
Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;
auto joint_and_links = make_joint(cMp, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(cMp, screw_axis);

// Create factor
auto factor = PoseFactor(example::wTp_key, example::wTc_key, example::q_key,
Expand Down Expand Up @@ -78,8 +77,7 @@ TEST(PoseFactor, breaking) {
Pose3 cMp = Pose3(Rot3(), Point3(-2, 0, 0));
Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;
auto joint_and_links = make_joint(cMp, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(cMp, screw_axis);
auto factor = PoseFactor(example::wTp_key, example::wTc_key, example::q_key,
example::cost_model, joint);

Expand Down Expand Up @@ -113,8 +111,7 @@ TEST(PoseFactor, breaking_rr) {

Vector6 screw_axis = (Vector6() << 1, 0, 0, 0, -1, 0).finished();
Pose3 cMp = j1->relativePoseOf(l1, 0.0);
auto joint_and_links = make_joint(cMp, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(cMp, screw_axis);
auto factor = PoseFactor(example::wTp_key, example::wTc_key, example::q_key,
example::cost_model, joint);

Expand All @@ -132,8 +129,7 @@ TEST(PoseFactor, nonzero_rest) {
Pose3 cMp = Pose3(Rot3::Rx(1), Point3(-2, 0, 0));
Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;
auto joint_and_links = make_joint(cMp, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(cMp, screw_axis);
auto factor = PoseFactor(example::wTp_key, example::wTc_key, example::q_key,
example::cost_model, joint);

Expand Down
3 changes: 1 addition & 2 deletions tests/testTorqueFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,7 @@ TEST(TorqueFactor, error) {
gtsam::Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;

auto joint_and_links = make_joint(kMj, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(kMj, screw_axis);

// Create factor.
auto cost_model = gtsam::noiseModel::Gaussian::Covariance(gtsam::I_1x1);
Expand Down
6 changes: 2 additions & 4 deletions tests/testTwistAccelFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,7 @@ TEST(TwistAccelFactor, error) {
gtsam::Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;

auto joint_and_links = make_joint(cMp, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(cMp, screw_axis);

// create factor
auto factor = TwistAccelFactor(example::cost_model, joint, 0);
Expand Down Expand Up @@ -86,8 +85,7 @@ TEST(TwistAccelFactor, error_1) {
gtsam::Pose3 cMp = gtsam::Pose3(gtsam::Rot3(), gtsam::Point3(-1, 0, 0));
gtsam::Vector6 screw_axis = (gtsam::Vector(6) << 0, 0, 1, 0, 1, 0).finished();

auto joint_and_links = make_joint(cMp, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(cMp, screw_axis);

auto factor = TwistAccelFactor(example::cost_model, joint, 0);
double q = 0, qVel = 0, qAccel = -9.8;
Expand Down
3 changes: 1 addition & 2 deletions tests/testTwistFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,7 @@ TEST(TwistFactor, error) {
gtsam::Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;

auto joint_and_links = make_joint(cMp, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(cMp, screw_axis);

auto factor = TwistFactor(example::cost_model, joint, 0);
double q = M_PI / 4, qVel = 10;
Expand Down
9 changes: 3 additions & 6 deletions tests/testWrenchEquivalenceFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,7 @@ TEST(WrenchEquivalenceFactor, error_1) {
Pose3 kMj = Pose3(Rot3(), Point3(-2, 0, 0));
Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;
auto joint_and_links = make_joint(kMj, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(kMj, screw_axis);
auto factor = WrenchEquivalenceFactor(example::cost_model, joint, 777);

// Check evaluateError.
Expand All @@ -80,8 +79,7 @@ TEST(WrenchEquivalenceFactor, error_2) {
Pose3 kMj = Pose3(Rot3(), Point3(-2, 0, 0));
Vector6 screw_axis;
screw_axis << 0, 0, 1, 0, 1, 0;
auto joint_and_links = make_joint(kMj, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(kMj, screw_axis);
auto factor = WrenchEquivalenceFactor(example::cost_model, joint, 777);

// Check evaluateError.
Expand Down Expand Up @@ -109,8 +107,7 @@ TEST(WrenchEquivalenceFactor, error_3) {
Pose3 kMj = Pose3(Rot3(), Point3(0, 0, -2));
Vector6 screw_axis;
screw_axis << 1, 0, 0, 0, -1, 0;
auto joint_and_links = make_joint(kMj, screw_axis);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(kMj, screw_axis);
auto factor = WrenchEquivalenceFactor(example::cost_model, joint, 777);

// Check evaluateError.
Expand Down
3 changes: 1 addition & 2 deletions tests/testWrenchPlanarFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,7 @@ gtsam::noiseModel::Gaussian::shared_ptr cost_model =
gtsam::noiseModel::Gaussian::Covariance(gtsam::I_3x3);
const DynamicsSymbol wrench_key = WrenchKey(2, 1, 777);
gtsam::Pose3 kMj; // doesn't matter
auto joint_and_links = make_joint(kMj, gtsam::Z_6x1);
auto joint = joint_and_links.first;
auto [joint, links] = make_joint(kMj, gtsam::Z_6x1);
} // namespace example

// Test wrench planar factor for x-axis
Expand Down

0 comments on commit 8238df2

Please sign in to comment.