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 all the scripts #385

Merged
merged 2 commits into from
Oct 11, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
12 changes: 10 additions & 2 deletions scripts/alejandro_yetong_01_id_four_bar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,16 @@ int main(int argc, char** argv) {
graph_builder.dynamicsFactorGraph(robot, 0);

// Inverse dynamics priors. We care about the torques.
gtsam::Vector joint_angles = gtsam::Vector::Zero(robot.numJoints());
gtsam::Vector joint_vels = gtsam::Vector::Zero(robot.numJoints());
gtsam::Vector joint_accels = gtsam::Vector::Zero(robot.numJoints());

for (size_t j = 0; j < robot.numJoints(); ++j) {
InsertJointAngle(&joint_angles_vels_accels, j, 0, joint_angles[j]);
InsertJointVel(&joint_angles_vels_accels, j, 0, joint_vels[j]);
InsertJointAccel(&joint_angles_vels_accels, j, 0, joint_accels[j]);
}

gtsam::NonlinearFactorGraph prior_factors =
graph_builder.inverseDynamicsPriors(robot, 0, joint_angles_vels_accels);

Expand All @@ -52,8 +61,7 @@ int main(int argc, char** argv) {
prior_factors.addPrior(PoseKey(i, 0), link->bMcom(),
gtsam::noiseModel::Constrained::All(6));
prior_factors.addPrior<gtsam::Vector6>(
TwistKey(i, 0), gtsam::Z_6x1,
gtsam::noiseModel::Constrained::All(6));
TwistKey(i, 0), gtsam::Z_6x1, gtsam::noiseModel::Constrained::All(6));
}
graph.add(prior_factors);

Expand Down
6 changes: 4 additions & 2 deletions scripts/gerry00_ForwardDynamicsPrismatic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,11 @@ int main(int argc, char** argv) {
InsertJointVel(&theta_and_theta_dot, j2, 0, 0.1);
InsertJointVel(&theta_and_theta_dot, j3, 0, 0.0);

std::vector<gtsam::Vector> taus;
// Insert torque values for all timesteps
for (int t = 0; t <= T; t++) {
taus.push_back(gtsam::Vector::Zero(3));
InsertTorque(&theta_and_theta_dot, j1, t, 0.0);
InsertTorque(&theta_and_theta_dot, j2, t, 0.0);
InsertTorque(&theta_and_theta_dot, j3, t, 0.0);
}
auto fd_priors =
graph_builder.trajectoryFDPriors(simple_rpr, T, theta_and_theta_dot);
Expand Down
1 change: 1 addition & 0 deletions scripts/nithya00_constrained_opt_benchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ int main(int argc, char** argv) {
};

/// Write results to files for plotting.
std::cout << "Writing resutls to penalty_data.txt and augl_data.txt for plotting" << std::endl;
std::ofstream penalty_file;
penalty_file.open("penalty_data.txt");
for (size_t i = 0; i < penalty_info.num_iters.size(); i++) {
Expand Down
5 changes: 5 additions & 0 deletions scripts/stephanie01_ForwardDynamicsThreeLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,11 @@ int main(int argc, char **argv) {

// Add forward dynamics priors to factor graph.
gtsam::Values values;
for (size_t j = 0; j < robot.numJoints(); ++j) {
InsertJointAngle(&values, j, 0, 0.0);
InsertJointVel(&values, j, 0, 0.0);
InsertTorque(&values, j, 0, 0.0);
}

auto priorFactors = graph_builder.forwardDynamicsPriors(robot, 0, values);
graph.add(priorFactors);
Expand Down
Loading