ROBOOP, A Robotics Object Oriented Package in C++
|
Dynamics simulation handling class. More...
#include <dynamics_sim.h>
Public Member Functions | |
Dynamics (Robot_basic *robot_) | |
Constructor. | |
void | set_dof (Robot_basic *robot_) |
Set the degree of freedom. More... | |
short | set_controller (const Control_Select &x) |
Set the control variable from the Control_Select reference. | |
short | set_trajectory (const Trajectory_Select &x) |
Set the path_select variable from the Trajectory_Select reference. | |
ReturnMatrix | set_robot_on_first_point_of_splines () |
Set the robot on first point of trajectory. More... | |
void | set_time_frame (const int nsteps) |
Set the number of iterations. | |
void | set_final_time (const double tf) |
Set the file time. | |
void | reset_time () |
Set the simulation time to the inital time. | |
void | Runge_Kutta4_Real_time () |
Runge Kutta solver for real time. | |
void | Runge_Kutta4 () |
Runge Kutta solver. | |
virtual void | plot () |
Virtual plot functions. | |
ReturnMatrix | xdot (const Matrix &xin) |
Obtain state derivative. More... | |
Static Public Member Functions | |
static Dynamics * | Instance () |
A pointer to Dynamics instance. Pointer is 0 if there is no instance (logic done in Constructor). | |
Public Attributes | |
bool | first_pass_Kutta |
First time in all Runge_Kutta4 functions. | |
int | ndof |
Degree of freedom. | |
int | dof_fix |
Degree of freedom + virtual link. | |
int | nsteps |
Numbers of iterations between. | |
double | h |
Runge Kutta temporary variable. | |
double | h2 |
Runge Kutta temporary variable. | |
double | time |
Time during simulation. | |
double | to |
Initial simulation time. | |
double | tf |
Final time used in Runge_Kutta4_Real_time. | |
double | tf_cont |
Final time used in Runge_Kutta4. | |
double | dt |
Time frame. | |
Matrix | k1 |
Runge Kutta temporary variable. | |
Matrix | k2 |
Runge Kutta temporary variable. | |
Matrix | k3 |
Runge Kutta temporary variable. | |
Matrix | k4 |
Runge Kutta temporary variable. | |
Matrix | x |
Stated vector obtain in Runge Kutta functions. | |
Matrix | xd |
Statd vector derivative obtaint in xdot function. | |
ColumnVector | q |
Joints positions. | |
ColumnVector | qp |
Joints velocities. | |
ColumnVector | qpp |
Joints accelerations. | |
ColumnVector | qd |
Desired joints positions. | |
ColumnVector | qpd |
Desired joints velocities. | |
ColumnVector | qppd |
Desired joints accelerations. | |
ColumnVector | tau |
Controller output torque. | |
ColumnVector | pd |
Desired end effector cartesian position. | |
ColumnVector | ppd |
Desired end effector cartesian velocity. | |
ColumnVector | pppd |
Desired end effector cartesian acceleration. | |
ColumnVector | wd |
Desired end effector cartesian angular velocity. | |
ColumnVector | wpd |
Desired end effector cartesian angular acceleration. | |
Quaternion | quatd |
Desired orientation express by a quaternion. | |
Control_Select | control |
Instance of Control_Select class. | |
Trajectory_Select | path_select |
Instance of Trajectory_Select class. | |
Robot_basic * | robot |
Pointer on Robot_basic class. | |
Static Public Attributes | |
static Dynamics * | instance = 0 |
Static pointer on Dynamics class. | |
Dynamics simulation handling class.
Definition at line 57 of file dynamics_sim.h.
void Dynamics::set_dof | ( | Robot_basic * | robot_ | ) |
Set the degree of freedom.
Obtain the degree of freedom from Robot_basic pointer. Some vectors will be resize with new current dof value.
Definition at line 106 of file dynamics_sim.cpp.
References dof_fix, first_pass_Kutta, Robot_basic::get_dof(), Robot_basic::get_fix(), ndof, q, qd, qp, qpd, qpp, qppd, robot, and tau.
ReturnMatrix Dynamics::set_robot_on_first_point_of_splines | ( | ) |
Set the robot on first point of trajectory.
Assigned the robot joints position to the first point of the trajectory if the latter is expressed in joint space, or assigned the robot joints position via inverse kinematics if the trajectory is expressed in cartesian space. The function return a message on the console if the format of the trajectory file is incorrect.
Definition at line 187 of file dynamics_sim.cpp.
References Robot_basic::get_q(), Robot_basic::inv_kin(), ndof, Spl_path::p_pdot(), Spl_path::p_pdot_pddot(), Trajectory_Select::path, Trajectory_Select::path_quat, path_select, pd, ppd, pppd, q, qd, qpd, Spl_Quaternion::quat_w(), quatd, Quaternion::R(), robot, Robot_basic::set_q(), tf_cont, Trajectory_Select::type, and wd.
Referenced by Runge_Kutta4(), and Runge_Kutta4_Real_time().
ReturnMatrix Dynamics::xdot | ( | const Matrix & | x | ) |
Obtain state derivative.
x,: | state vector (joint speed and joint velocity). |
The controller torque is applied if any controller has been selected, then the joint acceleration is obtained.
Definition at line 249 of file dynamics_sim.cpp.
References Robot_basic::acceleration(), control, dof_fix, dt, ndof, Spl_path::p_pdot(), Spl_path::p_pdot_pddot(), Trajectory_Select::path, Trajectory_Select::path_quat, path_select, pd, plot(), ppd, pppd, q, qd, qp, qpd, qpp, qppd, Spl_Quaternion::quat_w(), quatd, robot, Robot_basic::set_q(), Robot_basic::set_qp(), tau, time, Resolved_acc::torque_cmd(), Computed_torque_method::torque_cmd(), Proportional_Derivative::torque_cmd(), Control_Select::type, Trajectory_Select::type, wd, wpd, and xd.
Referenced by Runge_Kutta4(), and Runge_Kutta4_Real_time().