#include <Eigen/StdVector>
#include <iostream>
#include <fstream>
#include <thread>
#include <Eigen/Geometry>
#include <limits>
#include <Eigen/Dense>
#include <mutex>
#include <chrono>
#include <stdlib.h>
#include <time.h>
#include <ctime>
#include <string>
#include <atomic>
Go to the source code of this file.
|
#define | VERBOSE_MODE 1 |
|
#define | M_PI 3.1415926535897932384626433832795 |
|
#define | INF_LIM std::numeric_limits<double>::infinity() |
|
|
typedef unsigned int | uint |
|
typedef long long | llong |
|
typedef Eigen::MatrixXd | Mat |
|
typedef Eigen::Matrix4d | Mat4d |
|
typedef Eigen::Matrix3d | Mat3d |
|
typedef Eigen::Vector3d | Vec3d |
|
typedef Eigen::Vector2d | Vec2d |
|
typedef Eigen::VectorXd | Vec |
|
typedef Eigen::Quaterniond | Quat |
|
typedef std::chrono::high_resolution_clock::time_point | Time_point |
|
typedef std::chrono::high_resolution_clock | chrono_time |
|
typedef std::chrono::milliseconds | Ms |
|
typedef std::chrono::duration< double > | Delta_t |
|
|
bool | is_almost_equal (const double &a, const double &b, const double &tolerance=1E-4) |
|
bool | is_geq (const double &a, const double &b, const double &tolerance=1E-4) |
|
bool | is_leq (const double &a, const double &b, const double &tolerance=1E-4) |
|
double | rad_to_degree (const double &val) |
|
double | degree_to_rad (const double &val) |
|
◆ INF_LIM
#define INF_LIM std::numeric_limits<double>::infinity() |
◆ M_PI
#define M_PI 3.1415926535897932384626433832795 |
◆ VERBOSE_MODE
◆ chrono_time
◆ Delta_t
typedef std::chrono::duration<double> Delta_t |
◆ llong
◆ Mat
typedef Eigen::MatrixXd Mat |
◆ Mat3d
typedef Eigen::Matrix3d Mat3d |
◆ Mat4d
typedef Eigen::Matrix4d Mat4d |
◆ Ms
typedef std::chrono::milliseconds Ms |
◆ Quat
typedef Eigen::Quaterniond Quat |
◆ Time_point
typedef std::chrono::high_resolution_clock::time_point Time_point |
◆ uint
typedef unsigned int uint |
◆ Vec
typedef Eigen::VectorXd Vec |
◆ Vec2d
typedef Eigen::Vector2d Vec2d |
◆ Vec3d
typedef Eigen::Vector3d Vec3d |
◆ DH_type
DH two typical standards:
Enumerator |
---|
DH_standard | Standard DH approach.
|
DH_modified | Modified DH approach (better than standard!)
|
Definition at line 331 of file endorob.h.
◆ Joint_type
Currently supported joint types:
Enumerator |
---|
Revolute | Standard revolute joint.
|
Prismatic | Standard prismatic joint.
|
Rolling | Rolling-joint (two circular surfaces rolling against each other, changing the contact point)
|
Rolling_flex | Multi-stage flexible joint with Rolling-joints (two circular surfaces rolling against each other, changing the contact point)
|
Flex | For continuum or flexible joints (under development)
|
Definition at line 138 of file endorob.h.
◆ Solver_type
Currently supported solvers.
Traditional Jacobian based pseudo-inverse, Full-body Jacobien (pseudo-inverse), Damped Least Square, pseudo-inverse with null-space
Enumerator |
---|
Jacobian_pseudo_inverse | Simple pseudo-inverse approach.
|
Full_body_jacobian | Full body Jacobian approach for full joint control.
|
Jacobian_DLS | Damped least square approach.
|
Jacobian_pseudo_inverse_null_space | Pseudo iverse with null space.
|
Jacobian_transpose | Jacobian transpose.
|
Definition at line 148 of file endorob.h.
◆ degree_to_rad()
double degree_to_rad |
( |
const double & |
val | ) |
|
◆ is_almost_equal()
bool is_almost_equal |
( |
const double & |
a, |
|
|
const double & |
b, |
|
|
const double & |
tolerance = 1E-4 |
|
) |
| |
◆ is_geq()
bool is_geq |
( |
const double & |
a, |
|
|
const double & |
b, |
|
|
const double & |
tolerance = 1E-4 |
|
) |
| |
◆ is_leq()
bool is_leq |
( |
const double & |
a, |
|
|
const double & |
b, |
|
|
const double & |
tolerance = 1E-4 |
|
) |
| |
◆ rad_to_degree()
double rad_to_degree |
( |
const double & |
val | ) |
|