Endorob  1.4
A C++ Robotics library by P. Berthet-Rayne
Endorob Class Reference

This is the main Class: EndoRob that you can use to control your own weird looking robot... More...

#include <endorob.h>

Public Member Functions

 Endorob ()
 Default constructor. More...
 
 Endorob (const Solver_type &solver_type)
 Advanced constructor for full-body control. More...
 
 ~Endorob ()
 Default destructor. More...
 
void set_DH_convention (const DH_type &convention)
 Set DH convention: modified or standard. More...
 
void save_DH (std::string filename)
 Save DH entries to file. More...
 
void load_DH (std::string filename)
 Load DH entries from file. More...
 
void add_DH_entry (const double &a, const double &alpha, const double &d, const double &theta, const Joint_type &type, const double &a_bis=0, const double &theta_bis=0, const uint &flex=0)
 Setup robot DH table one entry at a time (Attention, modified DH convention by default) More...
 
void set_joint_limits (const double &min, const double &max)
 Set joint limits for current joint, radians for revolute or rolling joints, meters for prismatic. More...
 
void set_flex_resolution (const uint &res)
 Setup flex resolution for continuum robots: sampling/division into smaller revolute joints. More...
 
void set_flex_gradient (const Vec &vec)
 Setup flex gradient for continuum robots; used if the material is not uniformely bending. More...
 
void set_solver_type (Solver_type solver, const double &lambda=1)
 Set iterative solver type. More...
 
void set_tool_frame (const Mat4d &T)
 Set tool frame. More...
 
void set_base_frame (const Mat4d &T)
 Set base frame. More...
 
void set_mask (const Vec &mask)
 Set DOF reduction mask if your robot/instrument has less than 6 DOF. The mask is a 6x1 vector x,y,z,orientation 1, orientation 2, orientation 3. Set to 1 for active and to 0 for disabled. More...
 
void set_joint_coupling (const Vec &coupling)
 Set joint coupling if multiple joint are moving together (coupled) whether for mechanical coupling or flexible joint modelling (equally distributed) More...
 
void initialize ()
 Once all parameters set, initialize robot and start solver. More...
 
unsigned dof ()
 Get robot number of DOF (different to the number of joints if coupling is used) More...
 
unsigned joints ()
 Get robot number of joints (different to the number of DOF if coupling is used) More...
 
Mat4d get_forward_kinematics ()
 Get the tip pose / homogeneous matrix (forward kinematics) More...
 
Mat4d get_tip_pose ()
 Get the tip pose / homogeneous matrix (forward kinematics) More...
 
Vec3d get_tip_position ()
 Get the tip position / 3x1 vector (forward kinematics) More...
 
Mat4d get_forward_kinematics (const Vec &q)
 Get the forward kinematics for a specific joint vector q. More...
 
Mat get_Jacobian ()
 Get the Jacobian matrix of the robot in the current configuration. More...
 
Mat get_coupling_matrix (void)
 Get the joint coupling matrix. More...
 
void set_solver_target (const Mat4d &T)
 Set solver's target 4x4 homegenous matrix. More...
 
void set_solver_body_target (const Vec &vec)
 Set solver's full body target (for full body control) More...
 
void set_solver_body_target (const Vec &vec, const Mat4d &T)
 Set solver's full body target (for full body control) and desired tip transform. More...
 
Vec get_instant_IK_solution ()
 Request for solver's current solution,if solver is still running, the solution may not be valid. More...
 
Vec get_IK_solution ()
 Request for solver's converged solution, whether target is reached or not. More...
 
void set_q_vec (const Vec &q)
 Set robot's joint vector. More...
 
void reset_q_vec ()
 Reset robot to startup state. More...
 
Vec get_random_q_vec ()
 Get random feasible joint vector. More...
 
Vec get_body_vec ()
 Get full-body vector. More...
 
Vec get_body_vec (const Vec &q)
 Get full-body vector for specific joint vector. More...
 
unsigned get_iteration ()
 Get number of iterations. More...
 
double get_error_norm ()
 Get the error norm between the desired and current position. More...
 
double get_RMS_error ()
 Get the RMS per joint error between the desired and current position. More...
 
Vec get_error_vector ()
 Get the current error between the desired and current position. More...
 
Vec get_q_vec ()
 Get joint vector. More...
 
Vec get_full_q_vec ()
 Get complete joint vector before coupling. More...
 
Vec get_desired_curve ()
 Get desired curve. More...
 
void set_desired_curve (const Vec &curve)
 Set desired curve. More...
 
void set_desired_curve (const Vec &curve, const Mat4d &mat)
 Set desired curve and tip transform. More...
 
Vec solve_with_tentacle (Mat T_)
 
Vec follow_the_leader (const std::vector< Vec3d, Eigen::aligned_allocator< Vec3d >> path, const Vec &desired_shape, const double &translation)
 
Vec follow_the_leader_2 (const std::vector< Vec3d, Eigen::aligned_allocator< Vec3d >> path, const Vec &desired_shape, const double &translation)
 
Vec follow_the_leader_3 (Snake_Path path, const Vec &desired_shape, const double &translation)
 
Virtual_Snake follow_the_leader_weighted (Snake_Path path, const Virtual_Snake &desired_shape, const double &translation)
 
std::vector< DH_table_entryget_DH_table ()
 Get the full DH table of the robot. More...
 
Mat get_full_kinematics ()
 Get the full and complete forward kinematics as a nx4 matrix of homogeneous matrix for each link. More...
 
Vec set_vec_relative_to_base (const Vec &vec)
 
Mat get_snake_base ()
 
void set_solver_weight_mat (const uint &index, const double &val)
 Set the solver's weights value for a desired joint at a specific index. More...
 
void set_solver_weight_mat (const Vec &vec)
 
void set_solver_weight_vec (const uint &index, const double &val)
 
void set_robot_reference_frame (const Mat4d &T)
 
void enforce_joint_limits_mode (void)
 Enforce joint limit mode. In this mode the joint cannot exceed their joint limit. More...
 
void set_faulty_joint (const uint &joint, const double &val)
 Set a joint as faulty for Jacobian Compensation. More...
 
void disable_fault_tolerance ()
 Disable joint fault tolerance. More...
 
Vec get_faulty_q ()
 

Protected Member Functions

void calculate_full_forward_kinematics ()
 
Mat calculate_full_forward_kinematics (const Vec &q)
 
void calculate_jacobian ()
 
void calculate_full_body_jacobian ()
 
void calculate_full_mobile_body_jacobian ()
 
void threaded_solver (int a, int b)
 
void threaded_solver_2 (int a, int b)
 
void get_error (const Mat4d &Td, const Mat4d &Te)
 
Vec get_full_body_error ()
 
void get_full_mobile_body_error ()
 
Vec3d get_position_error (const Mat4d &Td, const Mat4d &Te)
 
Vec3d get_orientation_error (const Mat4d &Td, const Mat4d &Te)
 
bool solver_has_converged ()
 
bool solver_has_ended ()
 
Mat4d base_transformation_matrix (DH_table_entry DH, double q)
 
void calculate_pseudo_inverse ()
 
void calculate_pseudo_inverse_masked ()
 
void calculate_pseudo_inverse_DLS ()
 
Vec zero_thresholding (const Vec &q_vec, const double &val=M_PI/180/20)
 
Vec angle_modulus (const Vec &q_vec)
 
Mat mask_resize (const Mat &mat)
 
void apply_joint_coupling ()
 
void calculate_coupling_matrix_increase ()
 
void calculate_coupling_matrix_reduce ()
 
void calculte_dof_after_coupling ()
 
std::vector< std::string > split (const std::string &s, char delimiter, bool remove_empty)
 
bool check_joint_in_limit (const Vec &q)
 
void calculate_joint_LUT ()
 
void convert_fwd_k_into_vec ()
 
Vec convert_fwd_k_into_vec (Mat fwd_k)
 
Vec get_joint_limit_scalar ()
 
void pseudo_inverse_simple ()
 
void pseudo_inverse_null_space ()
 
void null_space_constraint_calculation ()
 
void pseudo_inverse_normal ()
 
void damped_least_square_method ()
 
void jacobian_transpose ()
 
void iterative_solve_equation ()
 
void check_for_cpu ()
 
void modify_error_with_f ()
 
void solve_for_mask ()
 
void check_for_convergence ()
 
void solve ()
 
void apply_joint_limits ()
 

Protected Attributes

uint m_joints
 
uint m_dof
 
Mat4d m_base_frame_T
 
Mat4d m_tool_frame_T
 
DH_type m_DH_convention
 
Mat4d m_tip_T
 
Mat4d m_target_T
 
Vec m_q_vec
 
Vec m_q_vec_rest
 
Vec m_prev_q_vec
 
Vec m_q_vec_for_user
 
std::vector< DH_table_entrym_DH_table
 
bool m_check_joint_limit_jacobian
 
double m_lambda
 
void(Endorob::* p_solver_type )(void)
 
Vec m_coupling_vector
 
Mat m_joint_coupling_matrix
 
Mat m_joint_coupling_reduce_dimension
 
bool m_apply_joint_coupling
 
bool m_rolling_joint_present
 
Vec m_xi_vec
 
Vec m_xi_vec_rest
 
Vec m_prev_xi_vec
 
Vec m_joint_lookup_table
 
std::thread * psolver
 
volatile bool m_start_solver
 
volatile bool m_run
 
volatile bool m_converged
 
volatile bool m_diverged
 
bool m_iteration_overflow
 
unsigned long m_iterations
 
bool m_do_not_start_solver
 
volatile bool m_wait_for_sync
 
volatile bool m_solver_pending
 
volatile bool m_thread_running
 
unsigned m_mask_dof
 
Vec m_mask_vector
 
bool m_apply_mask
 
Mat m_J
 
Mat m_J_inv
 
Mat m_J_masked
 
Mat m_J_inv_masked
 
Mat m_J_for_user
 
Mat m_J_vel
 
Mat m_J_rot
 
Vec3d m_p_e
 
Vec3d m_z_tmp
 
Vec3d m_p_tmp
 
Mat m_error_weights
 
Vec m_error_weights_vec
 
Vec m_phi
 
Vec m_alpha
 
Mat m_identity
 
unsigned m_joint_index_offset
 
bool m_apply_weighted_solution
 
Mat m_fwd_k_vec
 
Vec m_full_body_vec_current
 
Vec m_full_body_vec_desired
 
Vec m_virtual_snake
 
bool m_full_body_needed
 
Mat4d m_robot_frame_T
 
Mat4d m_global_frame_to_robot_increment
 
Mat4d m_robot_frame_to_global_increment
 
Vec m_error
 
Vec m_prev_error
 
Vec m_error_masked
 
Vec m_prev_error_masked
 
std::vector< Vec3d, Eigen::aligned_allocator< Vec3d > > m_robot_path
 
uint m_CPU_affinity
 
uint m_instantiation_index
 
std::vector< bool > m_faulty_joint_vec
 
std::atomic< bool > m_apply_fault_tolerance
 

Static Protected Attributes

static Vec m_virtual_robot
 
static uint m_CPU_amount = 0
 
static uint m_CPU_cpt = 0xFE
 
static volatile bool m_assigning_CPU = false
 
static uint m_instantiations = 0
 
static bool m_cpu_info_dispayed = false
 

Related Functions

(Note that these are not member functions.)

Mat4d invert_transform (const Mat4d &mat)
 Invert homogeneous matrix for opposite transformation. More...
 
Vec3d get_rpy (const Mat &mat)
 Get Roll Pitch and Yaw angles. More...
 
Vec3d get_Euler (const Mat &mat)
 Get Euler angles. More...
 
Mat4d set_rpy (const Mat &mat, Vec3d rpy)
 Set the roll pitch and yaw angles into a 4x4 homogeneous matrix. More...
 
Mat3d rot_x (const double &angle)
 Get the desired rotation matrix around the X axis rotated by a desired angle: More...
 
Mat3d rot_y (const double &angle)
 Get the desired rotation matrix around the Y axis rotated by a desired angle: More...
 
Mat3d rot_z (const double &angle)
 Get the desired rotation matrix around the Z axis rotated by a desired angle: More...
 
Mat3d rot_xyz (const double &angle, const Vec3d &axis)
 Get the desired rotation matrix formed by the angle and axis representation. More...
 
Mat4d rotate_transform_locally (const Mat4d &mat, const Mat3d &rot)
 Rotate transform locally. More...
 
Mat4d rotate_transform_around_P (const Mat4d &T, const Mat3d &rot, const Vec &P)
 Rotate transform around arbitrary point. More...
 
Mat4d rotate_transform_around_axis_and_P (const Mat4d &T, const double &angle, const Vec3d &axis, const Vec &P)
 Rotate transform around arbitrary axis and point. More...
 
Mat3d get_rotation_increment (const Mat3d &start, const Mat3d &goal)
 Get increment between two rotation matrices. More...
 
Vec get_vector_increment (const Vec &start, const Vec &goal)
 Get increment between two vectors. More...
 
Mat4d get_transform_increment (const Mat4d &start, const Mat4d &goal)
 Get increment between two transformation matrices (rotation and translation) More...
 
Vec3d project_point_onto_line (const Vec3d &P, const Vec3d &A, const Vec3d &B)
 Project point P onto line defined by AB (orthogonal projection) More...
 
Vec3d sphere_line_intersection (const double &radius, const Vec3d &center, const Vec3d &A, const Vec3d &B)
 Sphere line intersection. More...
 

Detailed Description

This is the main Class: EndoRob that you can use to control your own weird looking robot...

This robotics C++ library allows you to implement and control your own robots. All the linear algebra depends on the Eigen c++ library that you will need to get and install first. EndoRob uses the well know DH table convention to create your robot. Many functions are implemented to allow you to do forward kinematics, inverse kinematics using iterative solvers, full-body inverse kinematics, teleoperation, etc

Definition at line 420 of file endorob.h.

Constructor & Destructor Documentation

◆ Endorob() [1/2]

Endorob::Endorob ( )

Default constructor.

Creates an EndoRob object.

Definition at line 33 of file endorob.cpp.

◆ Endorob() [2/2]

Endorob::Endorob ( const Solver_type solver_type)

Advanced constructor for full-body control.

This constructor is used to control specifically all the joints for snake-like robots (i2Snake) and follow the leader navigation.

Definition at line 75 of file endorob.cpp.

◆ ~Endorob()

Endorob::~Endorob ( )

Default destructor.

N/A.

Definition at line 133 of file endorob.cpp.

Member Function Documentation

◆ add_DH_entry()

void Endorob::add_DH_entry ( const double &  a,
const double &  alpha,
const double &  d,
const double &  theta,
const Joint_type type,
const double &  a_bis = 0,
const double &  theta_bis = 0,
const uint flex = 0 
)

Setup robot DH table one entry at a time (Attention, modified DH convention by default)

Parameters
adouble argument from your DH table, in case of a rolling joint, a is the rolling joint radius * 2.
alphadouble argument from your DH table.
ddouble argument from your DH table.
thetadouble argument from your DH table.
typeJoint_type argument such as Prismatic, Revolute, Rolling.
a_bisoptional double argument specific to the rolling joint = rolling joint inner link length.
theta_bisoptional double argument specific to the rolling joint = post theta offset.
Returns
void
See also
enum Joint_type, DH_table_entry, save_DH(), load_DH()

Definition at line 283 of file endorob.cpp.

◆ angle_modulus()

Vec Endorob::angle_modulus ( const Vec q_vec)
protected

Definition at line 2918 of file endorob.cpp.

◆ apply_joint_coupling()

void Endorob::apply_joint_coupling ( )
protected

Definition at line 2960 of file endorob.cpp.

◆ apply_joint_limits()

void Endorob::apply_joint_limits ( )
protected

Definition at line 1485 of file endorob.cpp.

◆ base_transformation_matrix()

Mat4d Endorob::base_transformation_matrix ( DH_table_entry  DH,
double  q 
)
protected

Definition at line 3291 of file endorob.cpp.

◆ calculate_coupling_matrix_increase()

void Endorob::calculate_coupling_matrix_increase ( )
protected

Definition at line 2967 of file endorob.cpp.

◆ calculate_coupling_matrix_reduce()

void Endorob::calculate_coupling_matrix_reduce ( )
protected

Definition at line 2992 of file endorob.cpp.

◆ calculate_full_body_jacobian()

void Endorob::calculate_full_body_jacobian ( )
protected

Definition at line 1063 of file endorob.cpp.

◆ calculate_full_forward_kinematics() [1/2]

void Endorob::calculate_full_forward_kinematics ( )
protected

Definition at line 765 of file endorob.cpp.

◆ calculate_full_forward_kinematics() [2/2]

Mat Endorob::calculate_full_forward_kinematics ( const Vec q)
protected

Definition at line 861 of file endorob.cpp.

◆ calculate_full_mobile_body_jacobian()

void Endorob::calculate_full_mobile_body_jacobian ( )
protected

static‍/ bool first_run = true;

Definition at line 1158 of file endorob.cpp.

◆ calculate_jacobian()

void Endorob::calculate_jacobian ( )
protected

Definition at line 962 of file endorob.cpp.

◆ calculate_joint_LUT()

void Endorob::calculate_joint_LUT ( )
protected

Definition at line 3084 of file endorob.cpp.

◆ calculate_pseudo_inverse()

void Endorob::calculate_pseudo_inverse ( )
protected

Definition at line 3334 of file endorob.cpp.

◆ calculate_pseudo_inverse_DLS()

void Endorob::calculate_pseudo_inverse_DLS ( )
protected

Definition at line 3429 of file endorob.cpp.

◆ calculate_pseudo_inverse_masked()

void Endorob::calculate_pseudo_inverse_masked ( )
protected

Definition at line 3385 of file endorob.cpp.

◆ calculte_dof_after_coupling()

void Endorob::calculte_dof_after_coupling ( )
protected

Definition at line 3018 of file endorob.cpp.

◆ check_for_convergence()

void Endorob::check_for_convergence ( )
protected

Definition at line 1551 of file endorob.cpp.

◆ check_for_cpu()

void Endorob::check_for_cpu ( )
protected

Definition at line 3223 of file endorob.cpp.

◆ check_joint_in_limit()

bool Endorob::check_joint_in_limit ( const Vec q)
protected

Definition at line 3050 of file endorob.cpp.

◆ convert_fwd_k_into_vec() [1/2]

void Endorob::convert_fwd_k_into_vec ( )
protected

Definition at line 3101 of file endorob.cpp.

◆ convert_fwd_k_into_vec() [2/2]

Vec Endorob::convert_fwd_k_into_vec ( Mat  fwd_k)
protected

Definition at line 3114 of file endorob.cpp.

◆ damped_least_square_method()

void Endorob::damped_least_square_method ( )
protected

Definition at line 3195 of file endorob.cpp.

◆ disable_fault_tolerance()

void Endorob::disable_fault_tolerance ( )

Disable joint fault tolerance.

Definition at line 2913 of file endorob.cpp.

◆ dof()

unsigned Endorob::dof ( )

Get robot number of DOF (different to the number of joints if coupling is used)

Returns
an unsigned integer representing the number of DOF
See also
joints()

Definition at line 551 of file endorob.cpp.

◆ enforce_joint_limits_mode()

void Endorob::enforce_joint_limits_mode ( void  )

Enforce joint limit mode. In this mode the joint cannot exceed their joint limit.

Definition at line 2902 of file endorob.cpp.

◆ follow_the_leader()

Vec Endorob::follow_the_leader ( const std::vector< Vec3d, Eigen::aligned_allocator< Vec3d >>  path,
const Vec desired_shape,
const double &  translation 
)

Definition at line 2197 of file endorob.cpp.

◆ follow_the_leader_2()

Vec Endorob::follow_the_leader_2 ( const std::vector< Vec3d, Eigen::aligned_allocator< Vec3d >>  path,
const Vec desired_shape,
const double &  translation 
)

Definition at line 2267 of file endorob.cpp.

◆ follow_the_leader_3()

Vec Endorob::follow_the_leader_3 ( Snake_Path  path,
const Vec desired_shape,
const double &  translation 
)

Definition at line 2504 of file endorob.cpp.

◆ follow_the_leader_weighted()

Virtual_Snake Endorob::follow_the_leader_weighted ( Snake_Path  path,
const Virtual_Snake desired_shape,
const double &  translation 
)

Definition at line 2674 of file endorob.cpp.

◆ get_body_vec() [1/2]

Vec Endorob::get_body_vec ( )

Get full-body vector.

Returns
the full body vector
See also
TODO

Definition at line 2104 of file endorob.cpp.

◆ get_body_vec() [2/2]

Vec Endorob::get_body_vec ( const Vec q)

Get full-body vector for specific joint vector.

Parameters
qthe joint vector
Returns
the full body vector
See also
TODO

Definition at line 2109 of file endorob.cpp.

◆ get_coupling_matrix()

Mat Endorob::get_coupling_matrix ( void  )

Get the joint coupling matrix.

Returns
the nxn joint coupling matrix
See also
TODO

Definition at line 659 of file endorob.cpp.

◆ get_desired_curve()

Vec Endorob::get_desired_curve ( )

Get desired curve.

Returns
the desired curve
See also
TODO

Definition at line 1874 of file endorob.cpp.

◆ get_DH_table()

std::vector< DH_table_entry > Endorob::get_DH_table ( )

Get the full DH table of the robot.

Returns
a std vector of DH table entries
See also
TODO

Definition at line 2821 of file endorob.cpp.

◆ get_error()

void Endorob::get_error ( const Mat4d Td,
const Mat4d Te 
)
protected

Definition at line 1305 of file endorob.cpp.

◆ get_error_norm()

double Endorob::get_error_norm ( )

Get the error norm between the desired and current position.

Returns
the error norm
See also
TODO

Definition at line 2119 of file endorob.cpp.

◆ get_error_vector()

Vec Endorob::get_error_vector ( )

Get the current error between the desired and current position.

Returns
the error vector
See also
TODO

Definition at line 2142 of file endorob.cpp.

◆ get_faulty_q()

Vec Endorob::get_faulty_q ( )

Definition at line 1504 of file endorob.cpp.

◆ get_forward_kinematics() [1/2]

Mat4d Endorob::get_forward_kinematics ( )

Get the tip pose / homogeneous matrix (forward kinematics)

Returns
an homogeneous matrix representing the tip pose
See also
get_tip_pose(), get_tip_position()

Definition at line 561 of file endorob.cpp.

◆ get_forward_kinematics() [2/2]

Mat4d Endorob::get_forward_kinematics ( const Vec q)

Get the forward kinematics for a specific joint vector q.

Parameters
qthe desired joint vector
Returns
an 4x4 transformation matrix of the tip of the robot
See also
get_forward_kinematics(), get_tip_pose(), get_tip_position()

Definition at line 566 of file endorob.cpp.

◆ get_full_body_error()

Vec Endorob::get_full_body_error ( )
protected

Definition at line 1321 of file endorob.cpp.

◆ get_full_kinematics()

Mat Endorob::get_full_kinematics ( )

Get the full and complete forward kinematics as a nx4 matrix of homogeneous matrix for each link.

Returns
a nx4 matrix of the full forward kinematics
See also
TODO

Definition at line 2826 of file endorob.cpp.

◆ get_full_mobile_body_error()

void Endorob::get_full_mobile_body_error ( )
protected

Definition at line 1326 of file endorob.cpp.

◆ get_full_q_vec()

Vec Endorob::get_full_q_vec ( )

Get complete joint vector before coupling.

Returns
the joint vector
See also
TODO

Definition at line 1869 of file endorob.cpp.

◆ get_IK_solution()

Vec Endorob::get_IK_solution ( )

Request for solver's converged solution, whether target is reached or not.

Returns
the joint vector q
See also
TODO

Definition at line 1890 of file endorob.cpp.

◆ get_instant_IK_solution()

Vec Endorob::get_instant_IK_solution ( )

Request for solver's current solution,if solver is still running, the solution may not be valid.

Returns
the joint vector q
See also
TODO

Definition at line 1849 of file endorob.cpp.

◆ get_iteration()

unsigned Endorob::get_iteration ( )

Get number of iterations.

Returns
the amount of iteration
See also
TODO

Definition at line 2114 of file endorob.cpp.

◆ get_Jacobian()

Mat Endorob::get_Jacobian ( )

Get the Jacobian matrix of the robot in the current configuration.

Returns
the 6xn Jacobian matrix
See also
TODO

Definition at line 654 of file endorob.cpp.

◆ get_joint_limit_scalar()

Vec Endorob::get_joint_limit_scalar ( )
protected

Definition at line 3130 of file endorob.cpp.

◆ get_orientation_error()

Vec3d Endorob::get_orientation_error ( const Mat4d Td,
const Mat4d Te 
)
protected

Definition at line 1286 of file endorob.cpp.

◆ get_position_error()

Vec3d Endorob::get_position_error ( const Mat4d Td,
const Mat4d Te 
)
protected

Definition at line 1280 of file endorob.cpp.

◆ get_q_vec()

Vec Endorob::get_q_vec ( )

Get joint vector.

Returns
the joint vector
See also
TODO

Definition at line 1861 of file endorob.cpp.

◆ get_random_q_vec()

Vec Endorob::get_random_q_vec ( )

Get random feasible joint vector.

Returns
a random joint vector q
See also
TODO

Definition at line 1944 of file endorob.cpp.

◆ get_RMS_error()

double Endorob::get_RMS_error ( )

Get the RMS per joint error between the desired and current position.

Returns
the RMS error
See also
TODO

Definition at line 2125 of file endorob.cpp.

◆ get_snake_base()

Mat Endorob::get_snake_base ( )

Definition at line 2843 of file endorob.cpp.

◆ get_tip_pose()

Mat4d Endorob::get_tip_pose ( )

Get the tip pose / homogeneous matrix (forward kinematics)

Returns
an homogeneous matrix representing the tip pose
See also
get_forward_kinematics(), get_tip_position()

Definition at line 952 of file endorob.cpp.

◆ get_tip_position()

Vec3d Endorob::get_tip_position ( )

Get the tip position / 3x1 vector (forward kinematics)

Returns
an 3x1 vector representing the tip position
See also
get_forward_kinematics(), get_tip_pose()

Definition at line 957 of file endorob.cpp.

◆ initialize()

void Endorob::initialize ( )

Once all parameters set, initialize robot and start solver.

Returns
void

Definition at line 368 of file endorob.cpp.

◆ iterative_solve_equation()

void Endorob::iterative_solve_equation ( )
protected

Definition at line 3218 of file endorob.cpp.

◆ jacobian_transpose()

void Endorob::jacobian_transpose ( )
protected

Definition at line 3207 of file endorob.cpp.

◆ joints()

unsigned Endorob::joints ( )

Get robot number of joints (different to the number of DOF if coupling is used)

Returns
an unsigned integer representing the number of joints
See also
dof()

Definition at line 556 of file endorob.cpp.

◆ load_DH()

void Endorob::load_DH ( std::string  filename)

Load DH entries from file.

Parameters
filenamethe name of the file including the path
Returns
void
See also
set_DH_convention(), save_DH(), enum Joint_type

Definition at line 198 of file endorob.cpp.

◆ mask_resize()

Mat Endorob::mask_resize ( const Mat mat)
protected

Definition at line 2941 of file endorob.cpp.

◆ modify_error_with_f()

void Endorob::modify_error_with_f ( )
protected

Definition at line 3246 of file endorob.cpp.

◆ null_space_constraint_calculation()

void Endorob::null_space_constraint_calculation ( )
protected

Definition at line 3185 of file endorob.cpp.

◆ pseudo_inverse_normal()

void Endorob::pseudo_inverse_normal ( )
protected

◆ pseudo_inverse_null_space()

void Endorob::pseudo_inverse_null_space ( )
protected

Definition at line 3166 of file endorob.cpp.

◆ pseudo_inverse_simple()

void Endorob::pseudo_inverse_simple ( )
protected

Definition at line 3152 of file endorob.cpp.

◆ reset_q_vec()

void Endorob::reset_q_vec ( )

Reset robot to startup state.

See also
TODO

Definition at line 1927 of file endorob.cpp.

◆ save_DH()

void Endorob::save_DH ( std::string  filename)

Save DH entries to file.

Parameters
filenameFile name including the path to save the dh entries
Returns
void
See also
set_DH_convention(), load_DH(), enum Joint_type

Definition at line 158 of file endorob.cpp.

◆ set_base_frame()

void Endorob::set_base_frame ( const Mat4d T)

Set base frame.

Parameters
Ta homogeneous matrix describing the base frame
Returns
void

Definition at line 670 of file endorob.cpp.

◆ set_desired_curve() [1/2]

void Endorob::set_desired_curve ( const Vec curve)

Set desired curve.

Parameters
curvethe desired curve
See also
TODO

Definition at line 1879 of file endorob.cpp.

◆ set_desired_curve() [2/2]

void Endorob::set_desired_curve ( const Vec curve,
const Mat4d mat 
)

Set desired curve and tip transform.

Parameters
curvethe desired curve
matthe tip transform
See also
TODO

Definition at line 1884 of file endorob.cpp.

◆ set_DH_convention()

void Endorob::set_DH_convention ( const DH_type convention)

Set DH convention: modified or standard.

Parameters
enumDH_type argument stating the desired convention
Returns
void
See also
enum Joint_type, DH_table_entry, set_base_frame()

Definition at line 153 of file endorob.cpp.

◆ set_faulty_joint()

void Endorob::set_faulty_joint ( const uint joint,
const double &  val 
)

Set a joint as faulty for Jacobian Compensation.

Parameters
indexthe desired joint index
valjoint value
See also

Definition at line 2907 of file endorob.cpp.

◆ set_flex_gradient()

void Endorob::set_flex_gradient ( const Vec vec)

Setup flex gradient for continuum robots; used if the material is not uniformely bending.

Parameters
veca vector of doubles corresponding to the fraction of motion attributed to a joint (proximal section first; vector must be of norm = 1.0)
Returns
void
See also
set_flex_resolution()

Definition at line 337 of file endorob.cpp.

◆ set_flex_resolution()

void Endorob::set_flex_resolution ( const uint res)

Setup flex resolution for continuum robots: sampling/division into smaller revolute joints.

Parameters
resan unsigned int argument, the resolution (amount of division) of the flexible joint
Returns
void
See also
set_flex_gradient()

Definition at line 332 of file endorob.cpp.

◆ set_joint_coupling()

void Endorob::set_joint_coupling ( const Vec coupling)

Set joint coupling if multiple joint are moving together (coupled) whether for mechanical coupling or flexible joint modelling (equally distributed)

Parameters
couplingan nx1 vector (where n is your amount of DOF) filled as follow: give same index to coupled joints e.g. {0, 1, 2, 3, 4, 5, 4, 5, 6} here joints {4 and 6} are coupled as well as joints {5 and 7}
Returns
void

Definition at line 703 of file endorob.cpp.

◆ set_joint_limits()

void Endorob::set_joint_limits ( const double &  min,
const double &  max 
)

Set joint limits for current joint, radians for revolute or rolling joints, meters for prismatic.

Parameters
minthe minimal value that your joint can take.
maxthe maximal value that your joint can take.
Returns
void

Definition at line 320 of file endorob.cpp.

◆ set_mask()

void Endorob::set_mask ( const Vec mask)

Set DOF reduction mask if your robot/instrument has less than 6 DOF. The mask is a 6x1 vector x,y,z,orientation 1, orientation 2, orientation 3. Set to 1 for active and to 0 for disabled.

Parameters
maska 6x1 vector of 0's (disable) and 1's (enable)
Returns
void

Definition at line 675 of file endorob.cpp.

◆ set_q_vec()

void Endorob::set_q_vec ( const Vec q)

Set robot's joint vector.

Parameters
qthe joint vector
See also
TODO

Definition at line 1906 of file endorob.cpp.

◆ set_robot_reference_frame()

void Endorob::set_robot_reference_frame ( const Mat4d T)

Definition at line 2892 of file endorob.cpp.

◆ set_solver_body_target() [1/2]

void Endorob::set_solver_body_target ( const Vec vec)

Set solver's full body target (for full body control)

Parameters
vecthe full-body target vector
See also
TODO

Definition at line 2169 of file endorob.cpp.

◆ set_solver_body_target() [2/2]

void Endorob::set_solver_body_target ( const Vec vec,
const Mat4d T 
)

Set solver's full body target (for full body control) and desired tip transform.

Parameters
vecthe full-body target vector
Tthe desired tip transform
See also
TODO

Definition at line 2179 of file endorob.cpp.

◆ set_solver_target()

void Endorob::set_solver_target ( const Mat4d T)

Set solver's target 4x4 homegenous matrix.

Parameters
Tthe 4x4 transformation matrix
See also
TODO

Definition at line 2159 of file endorob.cpp.

◆ set_solver_type()

void Endorob::set_solver_type ( Solver_type  solver,
const double &  lambda = 1 
)

Set iterative solver type.

Parameters
solverSolver_type from the corresponding enum
lambdathe damping factor when using the damped least square solver
Returns
void

Definition at line 342 of file endorob.cpp.

◆ set_solver_weight_mat() [1/2]

void Endorob::set_solver_weight_mat ( const uint index,
const double &  val 
)

Set the solver's weights value for a desired joint at a specific index.

Parameters
indexthe desired joint index
valthe weight value
See also

Definition at line 2877 of file endorob.cpp.

◆ set_solver_weight_mat() [2/2]

void Endorob::set_solver_weight_mat ( const Vec vec)

Definition at line 2886 of file endorob.cpp.

◆ set_solver_weight_vec()

void Endorob::set_solver_weight_vec ( const uint index,
const double &  val 
)

Definition at line 2871 of file endorob.cpp.

◆ set_tool_frame()

void Endorob::set_tool_frame ( const Mat4d T)

Set tool frame.

Parameters
Ta homogeneous matrix describing the tool frame
Returns
void

Definition at line 665 of file endorob.cpp.

◆ set_vec_relative_to_base()

Vec Endorob::set_vec_relative_to_base ( const Vec vec)

Definition at line 2831 of file endorob.cpp.

◆ solve()

void Endorob::solve ( )
protected

Definition at line 1415 of file endorob.cpp.

◆ solve_for_mask()

void Endorob::solve_for_mask ( )
protected

Definition at line 1518 of file endorob.cpp.

◆ solve_with_tentacle()

Vec Endorob::solve_with_tentacle ( Mat  T_)

Definition at line 2190 of file endorob.cpp.

◆ solver_has_converged()

bool Endorob::solver_has_converged ( )
protected

Definition at line 2149 of file endorob.cpp.

◆ solver_has_ended()

bool Endorob::solver_has_ended ( )
protected

Definition at line 2154 of file endorob.cpp.

◆ split()

std::vector< std::string > Endorob::split ( const std::string &  s,
char  delimiter,
bool  remove_empty 
)
protected

Definition at line 3036 of file endorob.cpp.

◆ threaded_solver()

void Endorob::threaded_solver ( int  a,
int  b 
)
protected

Definition at line 1353 of file endorob.cpp.

◆ threaded_solver_2()

void Endorob::threaded_solver_2 ( int  a,
int  b 
)
protected

Definition at line 1586 of file endorob.cpp.

◆ zero_thresholding()

Vec Endorob::zero_thresholding ( const Vec q_vec,
const double &  val = M_PI/180/20 
)
protected

Definition at line 3277 of file endorob.cpp.

Friends And Related Function Documentation

◆ get_Euler()

Vec3d get_Euler ( const Mat mat)
related

Get Euler angles.

Parameters
mata 3x3 rotation matrix or a 4x4 homegenous matrix
Returns
a 3D vector with the Euler angles
See also
set_rpy(), rot_x(), rot_y(), rot_z(), rot_xyz(), get_rpy()

Definition at line 4814 of file endorob.cpp.

◆ get_rotation_increment()

Mat3d get_rotation_increment ( const Mat3d start,
const Mat3d goal 
)
related

Get increment between two rotation matrices.

Parameters
startthe 3x3 initial rotation matrix
goalthe 3x3 target rotation matrix
Returns
the 3x3 rotation matrix to go from start to goal
See also
TODO

Definition at line 4795 of file endorob.cpp.

◆ get_rpy()

Vec3d get_rpy ( const Mat mat)
related

Get Roll Pitch and Yaw angles.

Parameters
mata 3x3 rotation matrix or a 4x4 homegenous matrix
Returns
a 3D vector with the roll pitch and yaw angles
See also
set_rpy(), rot_x(), rot_y(), rot_z(), rot_xyz(), get_Euler()

Definition at line 1962 of file endorob.cpp.

◆ get_transform_increment()

Mat4d get_transform_increment ( const Mat4d start,
const Mat4d goal 
)
related

Get increment between two transformation matrices (rotation and translation)

Parameters
startthe 4x4 initial matrix
goalthe 4x4 goal matrix
Returns
the 4x4 matrix to go from start to goal
See also
TODO

Definition at line 4805 of file endorob.cpp.

◆ get_vector_increment()

Vec get_vector_increment ( const Vec start,
const Vec goal 
)
related

Get increment between two vectors.

Parameters
startthe 3x1 initial vector
goalthe 3x1 goal vector
Returns
the 3x1 vector to go from start to goal
See also
TODO

Definition at line 4800 of file endorob.cpp.

◆ invert_transform()

Mat4d invert_transform ( const Mat4d mat)
related

Invert homogeneous matrix for opposite transformation.

Parameters
mata 4x4 homogeneous matrix
Returns
the inverted matrix
See also
set_rpy(), rot_x(), rot_y(), rot_z(), rot_xyz(), get_Euler()

Definition at line 4832 of file endorob.cpp.

◆ project_point_onto_line()

Vec3d project_point_onto_line ( const Vec3d P,
const Vec3d A,
const Vec3d B 
)
related

Project point P onto line defined by AB (orthogonal projection)

Parameters
Pa 3D point
Aa 3D point
Ba 3d point
Returns
the coordinates of the projection
See also
TODO

Definition at line 2051 of file endorob.cpp.

◆ rot_x()

Mat3d rot_x ( const double &  angle)
related

Get the desired rotation matrix around the X axis rotated by a desired angle:

Parameters
angle(in radians)
Returns
a 3x3 rotation matrix
See also
get_rpy(), rot_y(), rot_z(), rot_xyz(), get_Euler()

Definition at line 1989 of file endorob.cpp.

◆ rot_xyz()

Mat3d rot_xyz ( const double &  angle,
const Vec3d axis 
)
related

Get the desired rotation matrix formed by the angle and axis representation.

Parameters
angle(in radians)
axisa 3D vector
Returns
the corresponding rotation matrix
See also
get_rpy(), rot_y(), rot_x(), rot_z(), get_Euler()

Definition at line 2004 of file endorob.cpp.

◆ rot_y()

Mat3d rot_y ( const double &  angle)
related

Get the desired rotation matrix around the Y axis rotated by a desired angle:

Parameters
angle(in radians)
Returns
a 3x3 rotation matrix
See also
get_rpy(), rot_x(), rot_z(), rot_xyz(), get_Euler()

Definition at line 1994 of file endorob.cpp.

◆ rot_z()

Mat3d rot_z ( const double &  angle)
related

Get the desired rotation matrix around the Z axis rotated by a desired angle:

Parameters
angle(in radians)
Returns
a 3x3 rotation matrix
See also
get_rpy(), rot_y(), rot_x(), rot_xyz(), get_Euler()

Definition at line 1999 of file endorob.cpp.

◆ rotate_transform_around_axis_and_P()

Mat4d rotate_transform_around_axis_and_P ( const Mat4d T,
const double &  angle,
const Vec3d axis,
const Vec P 
)
related

Rotate transform around arbitrary axis and point.

Parameters
Tthe 4x4 homogeneous matrix to be rotated
anglethe desired angle to rotate
axisthe desired 3D axis
Pthe 3D point where to do the rotation
Returns
the rotated transform
See also
TODO

Definition at line 2033 of file endorob.cpp.

◆ rotate_transform_around_P()

Mat4d rotate_transform_around_P ( const Mat4d T,
const Mat3d rot,
const Vec P 
)
related

Rotate transform around arbitrary point.

Parameters
Tthe 4x4 homogeneous matrix to be rotated
rotthe 3x3 rotation matrix
Pthe 3D point where to do the rotation
Returns
the rotated transform
See also
TODO

Definition at line 2018 of file endorob.cpp.

◆ rotate_transform_locally()

Mat4d rotate_transform_locally ( const Mat4d mat,
const Mat3d rot 
)
related

Rotate transform locally.

Parameters
matthe 4x4 homogeneous matrix to be rotated
rotthe 3x3 rotation matrix
Returns
the rotated transform
See also
TODO

Definition at line 2009 of file endorob.cpp.

◆ set_rpy()

Mat4d set_rpy ( const Mat mat,
Vec3d  rpy 
)
related

Set the roll pitch and yaw angles into a 4x4 homogeneous matrix.

Parameters
mata 4x4 homegenous matrix
rpya 3D vector with the RPY angles
Returns
a 4x4 homegenous matrix composed of the initial matrix and the rpy angles
See also
get_rpy(), rot_x(), rot_y(), rot_z(), rot_xyz(), get_Euler()

Definition at line 1980 of file endorob.cpp.

◆ sphere_line_intersection()

Vec3d sphere_line_intersection ( const double &  radius,
const Vec3d center,
const Vec3d A,
const Vec3d B 
)
related

Sphere line intersection.

Parameters
radiusthe sphere radius
centerthe sphere center
Athe start of the line
Bthe end of the line
Returns
the coordinates of the intersection
See also
TODO

Definition at line 2061 of file endorob.cpp.

Member Data Documentation

◆ m_alpha

Vec Endorob::m_alpha
protected

Definition at line 1007 of file endorob.h.

◆ m_apply_fault_tolerance

std::atomic<bool> Endorob::m_apply_fault_tolerance
protected

Definition at line 1039 of file endorob.h.

◆ m_apply_joint_coupling

bool Endorob::m_apply_joint_coupling
protected

Definition at line 976 of file endorob.h.

◆ m_apply_mask

bool Endorob::m_apply_mask
protected

Definition at line 997 of file endorob.h.

◆ m_apply_weighted_solution

bool Endorob::m_apply_weighted_solution
protected

Definition at line 1010 of file endorob.h.

◆ m_assigning_CPU

volatile bool Endorob::m_assigning_CPU = false
staticprotected

Definition at line 1031 of file endorob.h.

◆ m_base_frame_T

Mat4d Endorob::m_base_frame_T
protected

Definition at line 959 of file endorob.h.

◆ m_check_joint_limit_jacobian

bool Endorob::m_check_joint_limit_jacobian
protected

Definition at line 967 of file endorob.h.

◆ m_converged

volatile bool Endorob::m_converged
protected

Definition at line 986 of file endorob.h.

◆ m_coupling_vector

Vec Endorob::m_coupling_vector
protected

Definition at line 973 of file endorob.h.

◆ m_CPU_affinity

uint Endorob::m_CPU_affinity
protected

Definition at line 1030 of file endorob.h.

◆ m_CPU_amount

uint Endorob::m_CPU_amount = 0
staticprotected

Definition at line 1028 of file endorob.h.

◆ m_CPU_cpt

uint Endorob::m_CPU_cpt = 0xFE
staticprotected

Definition at line 1029 of file endorob.h.

◆ m_cpu_info_dispayed

bool Endorob::m_cpu_info_dispayed = false
staticprotected

Definition at line 1034 of file endorob.h.

◆ m_DH_convention

DH_type Endorob::m_DH_convention
protected

Definition at line 960 of file endorob.h.

◆ m_DH_table

std::vector<DH_table_entry> Endorob::m_DH_table
protected

Definition at line 966 of file endorob.h.

◆ m_diverged

volatile bool Endorob::m_diverged
protected

Definition at line 986 of file endorob.h.

◆ m_do_not_start_solver

bool Endorob::m_do_not_start_solver
protected

Definition at line 989 of file endorob.h.

◆ m_dof

uint Endorob::m_dof
protected

Definition at line 958 of file endorob.h.

◆ m_error

Vec Endorob::m_error
protected

Definition at line 1021 of file endorob.h.

◆ m_error_masked

Vec Endorob::m_error_masked
protected

Definition at line 1021 of file endorob.h.

◆ m_error_weights

Mat Endorob::m_error_weights
protected

Definition at line 1005 of file endorob.h.

◆ m_error_weights_vec

Vec Endorob::m_error_weights_vec
protected

Definition at line 1006 of file endorob.h.

◆ m_faulty_joint_vec

std::vector<bool> Endorob::m_faulty_joint_vec
protected

Definition at line 1038 of file endorob.h.

◆ m_full_body_needed

bool Endorob::m_full_body_needed
protected

Definition at line 1017 of file endorob.h.

◆ m_full_body_vec_current

Vec Endorob::m_full_body_vec_current
protected

Definition at line 1015 of file endorob.h.

◆ m_full_body_vec_desired

Vec Endorob::m_full_body_vec_desired
protected

Definition at line 1015 of file endorob.h.

◆ m_fwd_k_vec

Mat Endorob::m_fwd_k_vec
protected

Definition at line 1014 of file endorob.h.

◆ m_global_frame_to_robot_increment

Mat4d Endorob::m_global_frame_to_robot_increment
protected

Definition at line 1018 of file endorob.h.

◆ m_identity

Mat Endorob::m_identity
protected

Definition at line 1008 of file endorob.h.

◆ m_instantiation_index

uint Endorob::m_instantiation_index
protected

Definition at line 1035 of file endorob.h.

◆ m_instantiations

uint Endorob::m_instantiations = 0
staticprotected

Definition at line 1033 of file endorob.h.

◆ m_iteration_overflow

bool Endorob::m_iteration_overflow
protected

Definition at line 987 of file endorob.h.

◆ m_iterations

unsigned long Endorob::m_iterations
protected

Definition at line 988 of file endorob.h.

◆ m_J

Mat Endorob::m_J
protected

Definition at line 1000 of file endorob.h.

◆ m_J_for_user

Mat Endorob::m_J_for_user
protected

Definition at line 1001 of file endorob.h.

◆ m_J_inv

Mat Endorob::m_J_inv
protected

Definition at line 1000 of file endorob.h.

◆ m_J_inv_masked

Mat Endorob::m_J_inv_masked
protected

Definition at line 1000 of file endorob.h.

◆ m_J_masked

Mat Endorob::m_J_masked
protected

Definition at line 1000 of file endorob.h.

◆ m_J_rot

Mat Endorob::m_J_rot
protected

Definition at line 1002 of file endorob.h.

◆ m_J_vel

Mat Endorob::m_J_vel
protected

Definition at line 1002 of file endorob.h.

◆ m_joint_coupling_matrix

Mat Endorob::m_joint_coupling_matrix
protected

Definition at line 974 of file endorob.h.

◆ m_joint_coupling_reduce_dimension

Mat Endorob::m_joint_coupling_reduce_dimension
protected

Definition at line 975 of file endorob.h.

◆ m_joint_index_offset

unsigned Endorob::m_joint_index_offset
protected

Definition at line 1009 of file endorob.h.

◆ m_joint_lookup_table

Vec Endorob::m_joint_lookup_table
protected

Definition at line 980 of file endorob.h.

◆ m_joints

uint Endorob::m_joints
protected

Definition at line 957 of file endorob.h.

◆ m_lambda

double Endorob::m_lambda
protected

Definition at line 968 of file endorob.h.

◆ m_mask_dof

unsigned Endorob::m_mask_dof
protected

Definition at line 995 of file endorob.h.

◆ m_mask_vector

Vec Endorob::m_mask_vector
protected

Definition at line 996 of file endorob.h.

◆ m_p_e

Vec3d Endorob::m_p_e
protected

Definition at line 1003 of file endorob.h.

◆ m_p_tmp

Vec3d Endorob::m_p_tmp
protected

Definition at line 1004 of file endorob.h.

◆ m_phi

Vec Endorob::m_phi
protected

Definition at line 1007 of file endorob.h.

◆ m_prev_error

Vec Endorob::m_prev_error
protected

Definition at line 1021 of file endorob.h.

◆ m_prev_error_masked

Vec Endorob::m_prev_error_masked
protected

Definition at line 1021 of file endorob.h.

◆ m_prev_q_vec

Vec Endorob::m_prev_q_vec
protected

Definition at line 963 of file endorob.h.

◆ m_prev_xi_vec

Vec Endorob::m_prev_xi_vec
protected

Definition at line 979 of file endorob.h.

◆ m_q_vec

Vec Endorob::m_q_vec
protected

Definition at line 962 of file endorob.h.

◆ m_q_vec_for_user

Vec Endorob::m_q_vec_for_user
protected

Definition at line 964 of file endorob.h.

◆ m_q_vec_rest

Vec Endorob::m_q_vec_rest
protected

Definition at line 962 of file endorob.h.

◆ m_robot_frame_T

Mat4d Endorob::m_robot_frame_T
protected

Definition at line 1018 of file endorob.h.

◆ m_robot_frame_to_global_increment

Mat4d Endorob::m_robot_frame_to_global_increment
protected

Definition at line 1018 of file endorob.h.

◆ m_robot_path

std::vector<Vec3d, Eigen::aligned_allocator<Vec3d> > Endorob::m_robot_path
protected

Definition at line 1024 of file endorob.h.

◆ m_rolling_joint_present

bool Endorob::m_rolling_joint_present
protected

Definition at line 977 of file endorob.h.

◆ m_run

volatile bool Endorob::m_run
protected

Definition at line 985 of file endorob.h.

◆ m_solver_pending

volatile bool Endorob::m_solver_pending
protected

Definition at line 991 of file endorob.h.

◆ m_start_solver

volatile bool Endorob::m_start_solver
protected

Definition at line 985 of file endorob.h.

◆ m_target_T

Mat4d Endorob::m_target_T
protected

Definition at line 961 of file endorob.h.

◆ m_thread_running

volatile bool Endorob::m_thread_running
protected

Definition at line 992 of file endorob.h.

◆ m_tip_T

Mat4d Endorob::m_tip_T
protected

Definition at line 961 of file endorob.h.

◆ m_tool_frame_T

Mat4d Endorob::m_tool_frame_T
protected

Definition at line 959 of file endorob.h.

◆ m_virtual_robot

Vec Endorob::m_virtual_robot
staticprotected

Definition at line 1025 of file endorob.h.

◆ m_virtual_snake

Vec Endorob::m_virtual_snake
protected

Definition at line 1016 of file endorob.h.

◆ m_wait_for_sync

volatile bool Endorob::m_wait_for_sync
protected

Definition at line 990 of file endorob.h.

◆ m_xi_vec

Vec Endorob::m_xi_vec
protected

Definition at line 978 of file endorob.h.

◆ m_xi_vec_rest

Vec Endorob::m_xi_vec_rest
protected

Definition at line 978 of file endorob.h.

◆ m_z_tmp

Vec3d Endorob::m_z_tmp
protected

Definition at line 1004 of file endorob.h.

◆ p_solver_type

void(Endorob::* Endorob::p_solver_type) (void)
protected

Definition at line 969 of file endorob.h.

◆ psolver

std::thread* Endorob::psolver
protected

Definition at line 984 of file endorob.h.


The documentation for this class was generated from the following files: