class mpkBaseRobot |
The base class for all robots. It can represent arbitrary kinematic trees, free-flying objects and objects moving along complex constrained trajectories.
Joint* | joints Array of joints (created from jointdefs by constructor). |
int | num_joints Number of entries in joints. |
double* | params The vector of normalized parameters [0,1) of the robot (its DOFs). |
int | num_params Number of DOFs (entries in params, param_frozen and param_passive). |
param_info* | param_opts Attributes for the parameters |
double | scale_factor The scale factor of the robot (each instantiated robot can have a different scale factor). |
vector<selfcoll_pair> | selfcoll_info Pairs of joints whose links should be checked for collisions (can be set individually by the derived class). |
SoSeparator* | iv_graph Inventor scene graph for robot (note: must be updated explicitly using update_iv_transf()). |
int | tracepoint_joint_idx Index of joint for which the traced path in workspace will be visualized by the class TraceVis (typically the end-effector tip but can be an arbitrary point). |
mpkTransform | base_T Movable base transform for collision model of robot. |
SoTransform* | iv_base_T Movable base transform for scene graph of robot. |
mpkBaseRobot (const char* name, const char* rob_file_name, const mpkTransform& base_transf, double scalef=1.0) Constructs a robot with the given name from a file in .rob format. The robot can be placed at any place in the world coordinate frame using base_transf and it can be rescaled using scalef. | |
mpkBaseRobot (const char* name, int num_joints, JointDef* jointdefs, const mpkTransform& base_transf, double scalef=1.0) Constructs a robot with the given name from a 'hardcoded' description given by jointdefs. num_joints is the number of entries in jointdefs. The robot can be placed at any place in the world coordinate frame using base_transf and it can be rescaled using scalef. | |
void | compute_forward_kinematics () Compute transforms (Taccu) for all joints. |
void | compute_forward_kinematics (int joint_idx) Compute transforms (Taccu) for path along kinematic chain from joint_idx to root of kinematic tree. |
void | compute_forward_kinematics (int joint_idx, unsigned t, mpkTransformCache* cache) Compute transforms (Taccu) for path along kinematic chain from joint_idx to root of kinematic tree. This version takes advantage of the kinematics cache. |
void | update_iv_transf () Updates the transformations of the robot model in the scene graph. |
bool | collision (int i, int j, int model_id=0) Checks links i and j for collision. |
bool | collision (int i, double R[3][3], double T[3], PQP_Model* obstacle, int model_id=0) Checks link i and the given PQP model obstacle at pose (R,T) for collision. |
double | distance (int i, int j, double rel_err=0, int model_id=0) Returns the exact distance between the links i and j. |
double | distance (int i, double R[3][3], double T[3], PQP_Model* obstacle, double rel_err=0, int model_id=0) Returns the exact distance between link i and the given PQP model obstacle at pose (R,T). |
bool | closer_than_thres (int i, int j, double thres=0, int model_id=0) Determines if the exact distance between links i and j is smaller than thres. Note that this is much faster than exact distance computation. |
bool | closer_than_thres (int i, double R[3][3], double T[3], PQP_Model* obstacle, double thres=0, int model_id=0 ) Determines if the exact distance between link i the given PQP model obstacle at pose (R,T) is smaller than thres. Note that this is much faster than exact distance computation. |
void | translate_base (double dx, double dy, double dz) Translate kinematic tree by (dx,dy,dz) (moves entire robot). |
const char* | get_name () Returns the name of the robot as given in the scene file. |
virtual double | pathlen_upbound (const mpkConfig& q0, const mpkConfig& q1, int first_param_idx, int joint_idx, int root_idx=-1) Function that returns an upper bound on the motion of all points of the link model in the joint at joint_idx during a motion from q0 to q1. first_param_idx must tell the robot where its parameters start in the configuration vectors (which may contain multi-robot params). If root_idx >= 0, then the computation is w.r.t. the frame of joint root_idx (used for self-collision bounds of two links on the same kinematic chain). |
struct | JointDef Structure to define a joint. Each joint contains information about its parent joint, spatial transforms and an optional attached triangulated link model. This information is necessary to define a robot. |
struct | Joint : JointDef Structure to represent a joint (adds some working data to JointDef). The fields not present in JointDef are derived automatically from those in JointDef. |
struct | param_info Structure to bundle attributes of a single parameter |
struct | selfcoll_pair Self-collision pair structure (simply a pair of indices into joints). |
The constructor either reads the kinematics from a .rob file or takes the description directly as a pointer to an array (jointdefs). It creates a collision model of the robot and an inventor scene graph (for displaying only). Note that the scene graph is only loosely coupled to the collision model: an explicit call to update_iv_transf() is required to synchronize the inventor model with the collision model. This allows for more efficient computations during planning where displayed model should not move around. The array {@link params params} of size num_params contains all parameters of the robot. After changing an entry in this array, one of the functions {@link compute_forward_kinematics compute_forward_kinematics()} must be called to update the collision model.
Alphabetic index HTML hierarchy of classes or Java