This project provides a class-based C++ API for core Modern Robotics routines. The API is split into focused classes so you can include only what you need.
For a full guide, see the user manual: docs/user-manual.md.
API reference index: docs/api-manual.md.
Doxygen site: https://irayshon.github.io/WallE/
WallE::Tools- shared math helpers, SE(3)/so(3) utilities, JacobiansWallE::FK- forward kinematics in body or space framesWallE::IK- inverse kinematics in body or space framesWallE::InverseDynamics- inverse dynamics solverWallE::Dynamics- mass matrix, forces, forward dynamics, trajectoriesWallE::Trajectory- time scaling and trajectory generationWallE::RobotControl- computed torque control and simulation helpersWallE::MotionPlanning- placeholder for upcoming planning utilities
#include <Eigen/Dense>
#include <WallE/tools.h>
Eigen::Vector3d omega(0.0, 0.0, 1.0);
Eigen::Matrix3d so3 = WallE::Tools::VecToso3(omega);
Eigen::Matrix3d R = WallE::Tools::MatrixExp3(so3);#include <Eigen/Dense>
#include <WallE/fk.h>
Eigen::MatrixXd M = Eigen::MatrixXd::Identity(4, 4);
Eigen::MatrixXd Slist(6, 1);
Eigen::VectorXd thetalist(1);
Eigen::MatrixXd T = WallE::FK::FKinSpace(M, Slist, thetalist);#include <Eigen/Dense>
#include <WallE/ik.h>
Eigen::MatrixXd M = Eigen::MatrixXd::Identity(4, 4);
Eigen::MatrixXd Blist(6, 1);
Eigen::MatrixXd T = Eigen::MatrixXd::Identity(4, 4);
Eigen::VectorXd thetalist(1);
bool success = WallE::IK::IKinBody(Blist, M, T, thetalist, 1e-3, 1e-3);#include <Eigen/Dense>
#include <vector>
#include <WallE/dynamics.h>
Eigen::VectorXd thetalist(1);
std::vector<Eigen::MatrixXd> Mlist;
std::vector<Eigen::MatrixXd> Glist;
Eigen::MatrixXd Slist(6, 1);
Eigen::MatrixXd M = WallE::Dynamics::MassMatrix(thetalist, Mlist, Glist, Slist);#include <Eigen/Dense>
#include <vector>
#include <WallE/inverse_dynamics.h>
Eigen::VectorXd thetalist(1);
Eigen::VectorXd dthetalist(1);
Eigen::VectorXd ddthetalist(1);
Eigen::Vector3d g(0.0, 0.0, -9.81);
Eigen::VectorXd Ftip = Eigen::VectorXd::Zero(6);
std::vector<Eigen::MatrixXd> Mlist;
std::vector<Eigen::MatrixXd> Glist;
Eigen::MatrixXd Slist(6, 1);
Eigen::VectorXd tau = WallE::InverseDynamics::Compute(
thetalist, dthetalist, ddthetalist, g, Ftip, Mlist, Glist, Slist);#include <Eigen/Dense>
#include <WallE/trajectory.h>
Eigen::VectorXd thetastart(1);
Eigen::VectorXd thetaend(1);
Eigen::MatrixXd traj = WallE::Trajectory::JointTrajectory(
thetastart, thetaend, 2.0, 100, 5);#include <Eigen/Dense>
#include <vector>
#include <WallE/robot_control.h>
Eigen::VectorXd thetalist(1);
Eigen::VectorXd dthetalist(1);
Eigen::VectorXd eint(1);
Eigen::VectorXd thetalistd(1);
Eigen::VectorXd dthetalistd(1);
Eigen::VectorXd ddthetalistd(1);
Eigen::Vector3d g(0.0, 0.0, -9.81);
std::vector<Eigen::MatrixXd> Mlist;
std::vector<Eigen::MatrixXd> Glist;
Eigen::MatrixXd Slist(6, 1);
Eigen::VectorXd tau = WallE::RobotControl::ComputedTorque(
thetalist,
dthetalist,
eint,
thetalistd,
dthetalistd,
ddthetalistd,
g,
Mlist,
Glist,
Slist,
1.0,
0.0,
0.1);