![]() |
Endorob
1.4
A C++ Robotics library by P. Berthet-Rayne
|
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_entry > | get_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 () |
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 ¢er, const Vec3d &A, const Vec3d &B) |
Sphere line intersection. More... | |
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
Endorob::Endorob | ( | ) |
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 | ( | ) |
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)
a | double argument from your DH table, in case of a rolling joint, a is the rolling joint radius * 2. |
alpha | double argument from your DH table. |
d | double argument from your DH table. |
theta | double argument from your DH table. |
type | Joint_type argument such as Prismatic, Revolute, Rolling. |
a_bis | optional double argument specific to the rolling joint = rolling joint inner link length. |
theta_bis | optional double argument specific to the rolling joint = post theta offset. |
Definition at line 283 of file endorob.cpp.
Definition at line 2918 of file endorob.cpp.
|
protected |
Definition at line 2960 of file endorob.cpp.
|
protected |
Definition at line 1485 of file endorob.cpp.
|
protected |
Definition at line 3291 of file endorob.cpp.
|
protected |
Definition at line 2967 of file endorob.cpp.
|
protected |
Definition at line 2992 of file endorob.cpp.
|
protected |
Definition at line 1063 of file endorob.cpp.
|
protected |
Definition at line 765 of file endorob.cpp.
Definition at line 861 of file endorob.cpp.
|
protected |
static/ bool first_run = true;
Definition at line 1158 of file endorob.cpp.
|
protected |
Definition at line 962 of file endorob.cpp.
|
protected |
Definition at line 3084 of file endorob.cpp.
|
protected |
Definition at line 3334 of file endorob.cpp.
|
protected |
Definition at line 3429 of file endorob.cpp.
|
protected |
Definition at line 3385 of file endorob.cpp.
|
protected |
Definition at line 3018 of file endorob.cpp.
|
protected |
Definition at line 1551 of file endorob.cpp.
|
protected |
Definition at line 3223 of file endorob.cpp.
|
protected |
Definition at line 3050 of file endorob.cpp.
|
protected |
Definition at line 3101 of file endorob.cpp.
Definition at line 3114 of file endorob.cpp.
|
protected |
Definition at line 3195 of file endorob.cpp.
void Endorob::disable_fault_tolerance | ( | ) |
Disable joint fault tolerance.
Definition at line 2913 of file endorob.cpp.
unsigned Endorob::dof | ( | ) |
Get robot number of DOF (different to the number of joints if coupling is used)
Definition at line 551 of file endorob.cpp.
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.
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.
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.
Vec Endorob::follow_the_leader_3 | ( | Snake_Path | path, |
const Vec & | desired_shape, | ||
const double & | translation | ||
) |
Definition at line 2504 of file endorob.cpp.
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.
Vec Endorob::get_body_vec | ( | ) |
Get full-body vector.
Definition at line 2104 of file endorob.cpp.
Get full-body vector for specific joint vector.
q | the joint vector |
Definition at line 2109 of file endorob.cpp.
Mat Endorob::get_coupling_matrix | ( | void | ) |
Get the joint coupling matrix.
Definition at line 659 of file endorob.cpp.
Vec Endorob::get_desired_curve | ( | ) |
Get desired curve.
Definition at line 1874 of file endorob.cpp.
std::vector< DH_table_entry > Endorob::get_DH_table | ( | ) |
Get the full DH table of the robot.
Definition at line 2821 of file endorob.cpp.
Definition at line 1305 of file endorob.cpp.
double Endorob::get_error_norm | ( | ) |
Get the error norm between the desired and current position.
Definition at line 2119 of file endorob.cpp.
Vec Endorob::get_error_vector | ( | ) |
Get the current error between the desired and current position.
Definition at line 2142 of file endorob.cpp.
Vec Endorob::get_faulty_q | ( | ) |
Definition at line 1504 of file endorob.cpp.
Mat4d Endorob::get_forward_kinematics | ( | ) |
Get the tip pose / homogeneous matrix (forward kinematics)
Definition at line 561 of file endorob.cpp.
Get the forward kinematics for a specific joint vector q.
q | the desired joint vector |
Definition at line 566 of file endorob.cpp.
|
protected |
Definition at line 1321 of file endorob.cpp.
Mat Endorob::get_full_kinematics | ( | ) |
Get the full and complete forward kinematics as a nx4 matrix of homogeneous matrix for each link.
Definition at line 2826 of file endorob.cpp.
|
protected |
Definition at line 1326 of file endorob.cpp.
Vec Endorob::get_full_q_vec | ( | ) |
Get complete joint vector before coupling.
Definition at line 1869 of file endorob.cpp.
Vec Endorob::get_IK_solution | ( | ) |
Request for solver's converged solution, whether target is reached or not.
Definition at line 1890 of file endorob.cpp.
Vec Endorob::get_instant_IK_solution | ( | ) |
Request for solver's current solution,if solver is still running, the solution may not be valid.
Definition at line 1849 of file endorob.cpp.
unsigned Endorob::get_iteration | ( | ) |
Get number of iterations.
Definition at line 2114 of file endorob.cpp.
Mat Endorob::get_Jacobian | ( | ) |
Get the Jacobian matrix of the robot in the current configuration.
Definition at line 654 of file endorob.cpp.
|
protected |
Definition at line 3130 of file endorob.cpp.
Definition at line 1286 of file endorob.cpp.
Definition at line 1280 of file endorob.cpp.
Vec Endorob::get_q_vec | ( | ) |
Vec Endorob::get_random_q_vec | ( | ) |
Get random feasible joint vector.
Definition at line 1944 of file endorob.cpp.
double Endorob::get_RMS_error | ( | ) |
Get the RMS per joint error between the desired and current position.
Definition at line 2125 of file endorob.cpp.
Mat Endorob::get_snake_base | ( | ) |
Definition at line 2843 of file endorob.cpp.
Mat4d Endorob::get_tip_pose | ( | ) |
Get the tip pose / homogeneous matrix (forward kinematics)
Definition at line 952 of file endorob.cpp.
Vec3d Endorob::get_tip_position | ( | ) |
Get the tip position / 3x1 vector (forward kinematics)
Definition at line 957 of file endorob.cpp.
void Endorob::initialize | ( | ) |
Once all parameters set, initialize robot and start solver.
Definition at line 368 of file endorob.cpp.
|
protected |
Definition at line 3218 of file endorob.cpp.
|
protected |
Definition at line 3207 of file endorob.cpp.
unsigned Endorob::joints | ( | ) |
Get robot number of joints (different to the number of DOF if coupling is used)
Definition at line 556 of file endorob.cpp.
void Endorob::load_DH | ( | std::string | filename | ) |
Load DH entries from file.
filename | the name of the file including the path |
Definition at line 198 of file endorob.cpp.
Definition at line 2941 of file endorob.cpp.
|
protected |
Definition at line 3246 of file endorob.cpp.
|
protected |
Definition at line 3185 of file endorob.cpp.
|
protected |
|
protected |
Definition at line 3166 of file endorob.cpp.
|
protected |
Definition at line 3152 of file endorob.cpp.
void Endorob::reset_q_vec | ( | ) |
void Endorob::save_DH | ( | std::string | filename | ) |
Save DH entries to file.
filename | File name including the path to save the dh entries |
Definition at line 158 of file endorob.cpp.
void Endorob::set_base_frame | ( | const Mat4d & | T | ) |
Set base frame.
T | a homogeneous matrix describing the base frame |
Definition at line 670 of file endorob.cpp.
void Endorob::set_desired_curve | ( | const Vec & | curve | ) |
Set desired curve.
curve | the desired curve |
Definition at line 1879 of file endorob.cpp.
Set desired curve and tip transform.
curve | the desired curve |
mat | the tip transform |
Definition at line 1884 of file endorob.cpp.
void Endorob::set_DH_convention | ( | const DH_type & | convention | ) |
Set DH convention: modified or standard.
enum | DH_type argument stating the desired convention |
Definition at line 153 of file endorob.cpp.
void Endorob::set_faulty_joint | ( | const uint & | joint, |
const double & | val | ||
) |
Set a joint as faulty for Jacobian Compensation.
index | the desired joint index |
val | joint value |
Definition at line 2907 of file endorob.cpp.
void Endorob::set_flex_gradient | ( | const Vec & | vec | ) |
Setup flex gradient for continuum robots; used if the material is not uniformely bending.
vec | a vector of doubles corresponding to the fraction of motion attributed to a joint (proximal section first; vector must be of norm = 1.0) |
Definition at line 337 of file endorob.cpp.
void Endorob::set_flex_resolution | ( | const uint & | res | ) |
Setup flex resolution for continuum robots: sampling/division into smaller revolute joints.
res | an unsigned int argument, the resolution (amount of division) of the flexible joint |
Definition at line 332 of file endorob.cpp.
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)
coupling | an 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} |
Definition at line 703 of file endorob.cpp.
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.
min | the minimal value that your joint can take. |
max | the maximal value that your joint can take. |
Definition at line 320 of file endorob.cpp.
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.
mask | a 6x1 vector of 0's (disable) and 1's (enable) |
Definition at line 675 of file endorob.cpp.
void Endorob::set_q_vec | ( | const Vec & | q | ) |
Set robot's joint vector.
q | the joint vector |
Definition at line 1906 of file endorob.cpp.
void Endorob::set_robot_reference_frame | ( | const Mat4d & | T | ) |
Definition at line 2892 of file endorob.cpp.
void Endorob::set_solver_body_target | ( | const Vec & | vec | ) |
Set solver's full body target (for full body control)
vec | the full-body target vector |
Definition at line 2169 of file endorob.cpp.
Set solver's full body target (for full body control) and desired tip transform.
vec | the full-body target vector |
T | the desired tip transform |
Definition at line 2179 of file endorob.cpp.
void Endorob::set_solver_target | ( | const Mat4d & | T | ) |
Set solver's target 4x4 homegenous matrix.
T | the 4x4 transformation matrix |
Definition at line 2159 of file endorob.cpp.
void Endorob::set_solver_type | ( | Solver_type | solver, |
const double & | lambda = 1 |
||
) |
Set iterative solver type.
solver | Solver_type from the corresponding enum |
lambda | the damping factor when using the damped least square solver |
Definition at line 342 of file endorob.cpp.
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.
index | the desired joint index |
val | the weight value |
Definition at line 2877 of file endorob.cpp.
void Endorob::set_solver_weight_mat | ( | const Vec & | vec | ) |
Definition at line 2886 of file endorob.cpp.
void Endorob::set_solver_weight_vec | ( | const uint & | index, |
const double & | val | ||
) |
Definition at line 2871 of file endorob.cpp.
void Endorob::set_tool_frame | ( | const Mat4d & | T | ) |
Set tool frame.
T | a homogeneous matrix describing the tool frame |
Definition at line 665 of file endorob.cpp.
Definition at line 2831 of file endorob.cpp.
|
protected |
Definition at line 1415 of file endorob.cpp.
|
protected |
Definition at line 1518 of file endorob.cpp.
Definition at line 2190 of file endorob.cpp.
|
protected |
Definition at line 2149 of file endorob.cpp.
|
protected |
Definition at line 2154 of file endorob.cpp.
|
protected |
Definition at line 3036 of file endorob.cpp.
|
protected |
Definition at line 1353 of file endorob.cpp.
|
protected |
Definition at line 1586 of file endorob.cpp.
Definition at line 3277 of file endorob.cpp.
Get increment between two rotation matrices.
start | the 3x3 initial rotation matrix |
goal | the 3x3 target rotation matrix |
Definition at line 4795 of file endorob.cpp.
Get Roll Pitch and Yaw angles.
mat | a 3x3 rotation matrix or a 4x4 homegenous matrix |
Definition at line 1962 of file endorob.cpp.
Get increment between two transformation matrices (rotation and translation)
start | the 4x4 initial matrix |
goal | the 4x4 goal matrix |
Definition at line 4805 of file endorob.cpp.
Get increment between two vectors.
start | the 3x1 initial vector |
goal | the 3x1 goal vector |
Definition at line 4800 of file endorob.cpp.
Invert homogeneous matrix for opposite transformation.
mat | a 4x4 homogeneous matrix |
Definition at line 4832 of file endorob.cpp.
Project point P onto line defined by AB (orthogonal projection)
P | a 3D point |
A | a 3D point |
B | a 3d point |
Definition at line 2051 of file endorob.cpp.
|
related |
Get the desired rotation matrix around the X axis rotated by a desired angle:
angle | (in radians) |
Definition at line 1989 of file endorob.cpp.
Get the desired rotation matrix formed by the angle and axis representation.
angle | (in radians) |
axis | a 3D vector |
Definition at line 2004 of file endorob.cpp.
|
related |
Get the desired rotation matrix around the Y axis rotated by a desired angle:
angle | (in radians) |
Definition at line 1994 of file endorob.cpp.
|
related |
Get the desired rotation matrix around the Z axis rotated by a desired angle:
angle | (in radians) |
Definition at line 1999 of file endorob.cpp.
|
related |
Rotate transform around arbitrary axis and point.
T | the 4x4 homogeneous matrix to be rotated |
angle | the desired angle to rotate |
axis | the desired 3D axis |
P | the 3D point where to do the rotation |
Definition at line 2033 of file endorob.cpp.
Rotate transform around arbitrary point.
T | the 4x4 homogeneous matrix to be rotated |
rot | the 3x3 rotation matrix |
P | the 3D point where to do the rotation |
Definition at line 2018 of file endorob.cpp.
Rotate transform locally.
mat | the 4x4 homogeneous matrix to be rotated |
rot | the 3x3 rotation matrix |
Definition at line 2009 of file endorob.cpp.
Set the roll pitch and yaw angles into a 4x4 homogeneous matrix.
mat | a 4x4 homegenous matrix |
rpy | a 3D vector with the RPY angles |
Definition at line 1980 of file endorob.cpp.
|
related |
Sphere line intersection.
radius | the sphere radius |
center | the sphere center |
A | the start of the line |
B | the end of the line |
Definition at line 2061 of file endorob.cpp.
|
protected |
|
staticprotected |
|
staticprotected |
|
protected |
|
protected |
|
protected |