109 #error Must use C++ for the type Robot 119 static const char header_rcsid[] =
"$Id: robot.h,v 1.52 2006/05/16 16:11:15 gourdeau Exp $";
126 using namespace NEWMAT;
145 Link(
const int jt = 0,
const Real it = 0.0,
const Real id = 0.0,
147 const Real theta_max =
M_PI/2,
const Real it_off = 0.0,
const Real mass = 1.0,
148 const Real cmx = 0.0,
const Real cmy = 0.0,
const Real cmz = 0.0,
149 const Real ixx = 0.0,
const Real ixy = 0.0,
const Real ixz = 0.0,
150 const Real iyy = 0.0,
const Real iyz = 0.0,
const Real izz = 0.0,
151 const Real iIm = 0.0,
const Real iGr = 0.0,
const Real iB = 0.0,
152 const Real iCf = 0.0,
const bool dh =
true,
const bool min_inertial_para =
false,
153 const bool immobile =
false);
155 void transform(
const Real q);
182 void set_I(
const Matrix & I);
220 friend class Robotgl;
221 friend class mRobotgl;
223 Robot_basic(
const int ndof = 1,
const bool dh_parameter =
false,
224 const bool min_inertial_para =
false);
226 const bool min_inertial_para =
false);
228 const bool dh_parameter =
false,
const bool min_inertial_para =
false);
229 Robot_basic(
const std::string & filename,
const std::string & robotName,
230 const bool dh_parameter =
false,
const bool min_inertial_para =
false);
236 if(i < 1 || i > dof) error(
"i must be 1 <= i <= dof");
237 return links[i].get_q();
239 bool get_DH()
const {
return links[1].DH; }
242 int get_available_dof(
const int endlink)
const;
254 void set_q(
const Matrix & q);
256 if(i < 1 || i > dof) error(
"i must be 1 <= i <= dof");
257 links[i].transform(q);
268 virtual void robotType_inv_kin() = 0;
272 bool & converge) {
return inv_kin(Tobj,mj,dof,converge);}
273 virtual ReturnMatrix inv_kin(
const Matrix & Tobj,
const int mj,
const int endlink,
bool & converge);
278 virtual ReturnMatrix jacobian(
const int endlink,
const int ref)
const = 0;
279 virtual ReturnMatrix jacobian_dot(
const int ref=0)
const = 0;
280 ReturnMatrix jacobian_DLS_inv(
const double eps,
const double lambda_max,
const int ref=0)
const;
311 void error(
const std::string & msg1)
const;
313 ColumnVector *w, *wp, *vp, *
a, *f, *f_nv, *n, *n_nv, *F, *N, *p, *pp,
314 *dw, *dwp, *dvp, *da, *df, *dn, *dF, *dN, *dp,
321 void cleanUpPointers();
343 Robot(
const int ndof=1);
347 Robot(
const std::string & filename,
const std::string & robotName);
349 virtual void robotType_inv_kin();
353 virtual ReturnMatrix inv_kin(
const Matrix & Tobj,
const int mj,
const int endlink,
bool & converge);
358 virtual ReturnMatrix jacobian(
const int endlink,
const int ref)
const;
359 virtual ReturnMatrix jacobian_dot(
const int ref=0)
const;
395 mRobot(
const std::string & filename,
const std::string & robotName);
397 virtual void robotType_inv_kin();
399 virtual ReturnMatrix inv_kin(
const Matrix & Tobj,
const int mj,
const int endlink,
bool & converge);
406 virtual ReturnMatrix jacobian(
const int endlink,
const int ref)
const;
407 virtual ReturnMatrix jacobian_dot(
const int ref=0)
const;
444 mRobot_min_para(
const std::string & filename,
const std::string & robotName);
446 virtual void robotType_inv_kin();
448 virtual ReturnMatrix inv_kin(
const Matrix & Tobj,
const int mj,
const int endlink,
bool & converge);
455 virtual ReturnMatrix jacobian(
const int endlink,
const int ref)
const;
456 virtual ReturnMatrix jacobian_dot(
const int ref=0)
const;
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
void set_B(const Real B_)
Set B.
virtual ~mRobot_min_para()
Destructor.
bool get_DH(void) const
Return DH value.
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
bool get_DH() const
Return true if in DH notation, false otherwise.
Real get_theta_min(void) const
Return theta_min.
virtual ~mRobot()
Destructor.
int fix
Virtual link, used with modified DH notation.
int get_dof() const
Return dof.
Real get_theta_max(void) const
Return theta_max.
Link * links
Pointer on Link cclass.
bool Puma_DH(const Robot_basic &robot)
Return true if the robot is like a Puma on DH notation.
void set_immobile(bool im)
Set immobile.
bool immobile
true if the joint is to be considered locked - ignored for inverse kinematics, but can still be reass...
ReturnMatrix get_available_qpp(void) const
Return the joint acceleration vector of available (non-immobile) joints.
bool Rhino_mDH(const Robot_basic &robot)
Return true if the robot is like a Rhino on modified DH notation.
void set_q(const Real q, const int i)
Real get_Cf(void) const
Return Cf.
Real get_d(void) const
Return d.
Matrix I
Inertia matrix w.r.t. center of mass and link coordinate system orientation.
bool Schilling_mDH(const Robot_basic &robot)
Return true if the robot is like a Schilling on modified DH notation.
static const char header_rcsid[]
RCS/CVS version.
ReturnMatrix get_q(void) const
Return the joint position vector.
EnumRobotType robotType
Robot type.
int get_available_dof() const
Counts number of currently non-immobile links.
bool get_immobile(void) const
Return immobile.
ReturnMatrix get_I(void) const
Return I.
ReturnMatrix get_p(void) const
Return p.
Real get_joint_offset(void) const
Return joint_offset.
void set_Im(const Real Im_)
Set Im.
Real get_B(void) const
Return B.
Virtual base robot class.
void set_m(const Real m_)
Set m.
Modified DH notation robot class.
bool Puma_mDH(const Robot_basic &robot)
Return true if the robot is like a Puma on modified DH notation.
Real get_alpha(void) const
Return alpha.
int get_fix() const
Return fix.
Real theta_min
Min joint angle.
Real get_theta(void) const
Return theta.
Matrix R
Orientation matrix of actual link w.r.t to previous link.
Real get_Im(void) const
Return Im.
The usual rectangular matrix.
ReturnMatrix get_available_q(void) const
Return the joint position vector of available (non-immobile) joints.
FloatVector FloatVector * a
void set_Cf(const Real Cf_)
Set Cf.
Modified DH notation and minimal inertial parameters robot class.
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
ReturnMatrix get_available_qp(void) const
Return the joint velocity vector of available (non-immobile) joints.
ReturnMatrix get_mc(void)
Return mc.
Real get_Gr(void) const
Return Gr.
bool Rhino_DH(const Robot_basic &robot)
Return true if the robot is like a Rhino on DH notation.
FloatVector FloatVector FloatVector * alpha
Real get_m(void) const
Return m.
ColumnVector mc
Mass center of gravity (used if min_para = true).
void perturb_robot(Robot_basic &robot, const double f=0.1)
Modify a robot.
ColumnVector r
Position of center of mass w.r.t. link coordinate system (min_para=F).
int get_joint_type(void) const
Return the joint type.
Real get_a(void) const
Return a.
int joint_type
Joint type.
bool Schilling_DH(const Robot_basic &robot)
Return true if the robot is like a Schilling on DH notation.
bool min_para
Minimum inertial parameter.
Real qpp
Joint acceleration.
Matrix * R
Temprary rotation matrix.
ReturnMatrix get_r(void)
Return r.
virtual ~Robot()
Destructor.
ReturnMatrix inv_kin(const Matrix &Tobj, const int mj, bool &converge)
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
ColumnVector z0
Axis vector at each joint.
Real get_q(const int i) const
EnumRobotType
enum EnumRobotType