Skip to content
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
15 changes: 15 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -119,3 +119,18 @@ option(GTDYNAMICS_BUILD_SCRIPTS "Build all scripts" OFF)
if(GTDYNAMICS_BUILD_SCRIPTS)
add_subdirectory(scripts)
endif()

message(STATUS "===============================================================")
message(STATUS "================ Configuration Options ======================")
message(STATUS "Project : ${PROJECT_NAME}")
message(STATUS "CMAKE_CXX_COMPILER_ID type : ${CMAKE_CXX_COMPILER_ID}")
message(STATUS "CMAKE_CXX_COMPILER_VERSION : ${CMAKE_CXX_COMPILER_VERSION}")
message(STATUS "GTSAM Version : ${GTSAM_VERSION}")
message(STATUS "Boost Version : ${Boost_VERSION}")
message(STATUS "Sdformat Version : ${sdformat8_VERSION}")
message(STATUS "Build Python : ${GTDYNAMICS_BUILD_PYTHON}")
if(GTDYNAMICS_BUILD_PYTHON)
message(STATUS "Python Version : ${WRAP_PYTHON_VERSION}")
endif()
message(STATUS "Build Scripts : ${GTDYNAMICS_BUILD_SCRIPTS}")
message(STATUS "===============================================================")
26 changes: 14 additions & 12 deletions scripts/alejandro_yetong_01_id_four_bar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,20 +14,21 @@
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/slam/PriorFactor.h>


#include <iostream>
#include <fstream>
#include <iostream>

#include "gtdynamics/dynamics/DynamicsGraph.h"
#include "gtdynamics/universal_robot/RobotModels.h"
#include "gtdynamics/factors/MinTorqueFactor.h"
#include "gtdynamics/universal_robot/RobotModels.h"
#include "gtdynamics/utils/initialize_solution_utils.h"

using namespace gtdynamics;
using namespace gtdynamics;

int main(int argc, char** argv) {
using four_bar_linkage::robot, four_bar_linkage::planar_axis,
four_bar_linkage::joint_angles, four_bar_linkage::joint_vels;
using four_bar_linkage::joint_angles;
using four_bar_linkage::joint_vels;
using four_bar_linkage::planar_axis;
using four_bar_linkage::robot;

gtsam::Vector3 gravity(0, -10, 0);
robot.fixLink("l1");
Expand All @@ -37,9 +38,9 @@ int main(int argc, char** argv) {
std::cout << "-------------" << std::endl;

// Build the dynamics graph.
auto graph_builder = DynamicsGraph();
gtsam::NonlinearFactorGraph graph = graph_builder.dynamicsFactorGraph(
robot, 0, gravity, planar_axis);
auto graph_builder = DynamicsGraph(gravity, planar_axis);
gtsam::NonlinearFactorGraph graph =
graph_builder.dynamicsFactorGraph(robot, 0);

// Inverse dynamics priors. We care about the torques.
gtsam::Vector joint_accels = gtsam::Vector::Zero(robot.numJoints());
Expand All @@ -61,8 +62,8 @@ int main(int argc, char** argv) {
// Add min torque factor to each joint. This factor minimizes torque squared.
for (auto joint : robot.joints())
graph.add(
MinTorqueFactor(TorqueKey(joint->id(), 0),
gtsam::noiseModel::Gaussian::Covariance(gtsam::I_1x1)));
MinTorqueFactor(internal::TorqueKey(joint->id(), 0),
gtsam::noiseModel::Gaussian::Covariance(gtsam::I_1x1)));

// Initialize solution.
gtsam::Values init_values = ZeroValues(robot, 0);
Expand All @@ -79,7 +80,8 @@ int main(int argc, char** argv) {
gtsam::Values results = optimizer.optimize();

std::cout << "\033[1;31mError: " << graph.error(results) << "\033[0m"
<< std::endl << "-------------" << std::endl;
<< std::endl
<< "-------------" << std::endl;

// Save fg visualization.
// graph_builder.saveGraph("../../visualization/factor_graph.json", graph,
Expand Down
Loading