39 static const char rcsid[] =
"$Id: dynamics_sim.cpp,v 1.6 2006/05/19 21:05:57 gourdeau Exp $";
47 using namespace NEWMAT;
168 cerr <<
"Dynamics::set_controller: mismatch degree of freedom between robot and controller." << endl;
183 cerr <<
"Dynamics::set_trajectory: controller space and trajectory space are not compatible.\n" 184 <<
" Both should be in joint space or in cartesian space." << endl;
207 cerr <<
"Dynamics::set_robot_on_first_point_of_spines: invalid joint space path." << endl;
223 Matrix Tobj(4,4); Tobj = 0;
242 cerr <<
"Dynamics::set_robot_on_first_point_of_spines: invalid cartesian path." << endl;
281 cerr <<
"Dynamics::xdot: Cartesian path can not be used with CTM controller." << endl;
298 cerr <<
"Dynamics::xdot: Cartesian path can not be used with CTM controller." << endl;
316 cerr <<
"Dynamics::xdot: Joint Space path can not be used with RRA controller." << endl;
364 for (
int i = 1; i <=
nsteps; i++) {
ReturnMatrix R() const
Rotation matrix from a unit quaternion.
double to
Initial simulation time.
short type
Cartesian or joint space.
Matrix x
Stated vector obtain in Runge Kutta functions.
double tf
Final time used in Runge_Kutta4_Real_time.
ColumnVector qpd
Desired joints velocities.
ReturnMatrix xdot(const Matrix &xin)
Obtain state derivative.
ColumnVector qpp
Joints accelerations.
int get_dof() const
Return dof.
ColumnVector pd
Desired end effector cartesian position.
void Runge_Kutta4()
Runge Kutta solver.
ReturnMatrix torque_cmd(Robot_basic &robot, const ColumnVector &pdpp, const ColumnVector &pdp, const ColumnVector &pd, const ColumnVector &wdp, const ColumnVector &wd, const Quaternion &qd, const short link_pc, const Real dt)
Output torque.
Quaternion quatd
Desired orientation express by a quaternion.
virtual void plot()
Virtual plot functions.
int nsteps
Numbers of iterations between.
Robots class definitions.
double tf_cont
Final time used in Runge_Kutta4.
double h2
Runge Kutta temporary variable.
ReturnMatrix torque_cmd(Robot_basic &robot, const ColumnVector &qd, const ColumnVector &qpd, const ColumnVector &qppd)
Output torque.
Matrix k3
Runge Kutta temporary variable.
Robot_basic * robot
Pointer on Robot_basic class.
ColumnVector qppd
Desired joints accelerations.
Header file for Dynamics definitions.
Dynamics(Robot_basic *robot_)
Constructor.
static Dynamics * Instance()
A pointer to Dynamics instance. Pointer is 0 if there is no instance (logic done in Constructor)...
Trajectory class selection.
ReturnMatrix torque_cmd(Robot_basic &robot, const ColumnVector &qd, const ColumnVector &qpd)
Output torque.
Proportional_Derivative pd
Spl_path path
Spl_path instance.
Matrix k2
Runge Kutta temporary variable.
void set_dof(Robot_basic *robot_)
Set the degree of freedom.
double time
Time during simulation.
ColumnVector wpd
Desired end effector cartesian angular acceleration.
short quat_w(const Real t, Quaternion &s, ColumnVector &w)
Quaternion interpollation and angular velocity.
Trajectory_Select path_select
Instance of Trajectory_Select class.
ReturnMatrix acceleration(const ColumnVector &q, const ColumnVector &qp, const ColumnVector &tau)
Joints acceleration without contact force.
double h
Runge Kutta temporary variable.
Spl_Quaternion path_quat
Spl_Quaternion instance.
int ndof
Degree of freedom.
void set_time_frame(const int nsteps)
Set the number of iterations.
Computed_torque_method ctm
void set_q(const ColumnVector &q)
Set the joint position vector.
Virtual base robot class.
ColumnVector q
Joints positions.
Matrix xd
Statd vector derivative obtaint in xdot function.
int get_fix() const
Return fix.
ColumnVector tau
Controller output torque.
The usual rectangular matrix.
short p_pdot_pddot(const Real time, ColumnVector &p, ColumnVector &pdot, ColumnVector &pdotdot)
Position, velocity and acceleration vector at time t.
short set_trajectory(const Trajectory_Select &x)
Set the path_select variable from the Trajectory_Select reference.
void set_final_time(const double tf)
Set the file time.
ReturnMatrix set_robot_on_first_point_of_splines()
Set the robot on first point of trajectory.
ColumnVector qp
Joints velocities.
Matrix k4
Runge Kutta temporary variable.
bool first_pass_Kutta
First time in all Runge_Kutta4 functions.
ColumnVector ppd
Desired end effector cartesian velocity.
void set_qp(const ColumnVector &qp)
Set the joint velocity vector.
GetSubMatrix SubMatrix(int fr, int lr, int fc, int lc) const
short space_type
JOINT_SPACE or CARTESIAN_SPACE.
void reset_time()
Set the simulation time to the inital time.
int get_dof()
Return the degree of freedom.
virtual ReturnMatrix inv_kin(const Matrix &Tobj, const int mj=0)
Numerical inverse kinematics. See inv_kin(const Matrix & Tobj, const int mj, const int endlink...
ColumnVector wd
Desired end effector cartesian angular velocity.
ColumnVector pppd
Desired end effector cartesian acceleration.
static const char rcsid[]
RCS/CVS version.
short p_pdot(const Real time, ColumnVector &p, ColumnVector &pdot)
Position and velocity vector at time t.
short type
Type of controller: PD, CTM,...
Matrix k1
Runge Kutta temporary variable.
void Runge_Kutta4_Real_time()
Runge Kutta solver for real time.
Control_Select control
Instance of Control_Select class.
int dof_fix
Degree of freedom + virtual link.
short set_controller(const Control_Select &x)
Set the control variable from the Control_Select reference.
Dynamics simulation handling class.
Real get_q(const int i) const
ColumnVector qd
Desired joints positions.
static Dynamics * instance
Static pointer on Dynamics class.