dynamics_sim.h
Go to the documentation of this file.
1 /*
2 Copyright (C) 2002-2004 Etienne Lachance
3 
4 This library is free software; you can redistribute it and/or modify
5 it under the terms of the GNU Lesser General Public License as
6 published by the Free Software Foundation; either version 2.1 of the
7 License, or (at your option) any later version.
8 
9 This library is distributed in the hope that it will be useful,
10 but WITHOUT ANY WARRANTY; without even the implied warranty of
11 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 GNU Lesser General Public License for more details.
13 
14 You should have received a copy of the GNU Lesser General Public
15 License along with this library; if not, write to the Free Software
16 Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
17 
18 
19 Report problems and direct all questions to:
20 
21 email: etienne.lachance@polymtl.ca or richard.gourdeau@polymtl.ca
22 
23 -------------------------------------------------------------------------------
24 Revision_history:
25 
26 2005/06/10: Etienne Lachance
27  -The desired joint acceleration was missing in the computed torque method.
28 -------------------------------------------------------------------------------
29 */
30 
31 
32 #ifndef DYNAMICS_SIM_H
33 #define DYNAMICS_SIM_H
34 
40 static const char header_dynamics_sim_rcsid[] = "$Id: dynamics_sim.h,v 1.4 2006/05/16 16:11:15 gourdeau Exp $";
42 
43 #include "control_select.h"
44 #include "quaternion.h"
45 #include "trajectory.h"
46 #include "utils.h"
47 
48 #ifdef use_namespace
49 namespace ROBOOP {
50  using namespace NEWMAT;
51 #endif
52 
53 class Robot_basic;
54 
55 
60 class Dynamics
61 {
62 public:
63  Dynamics(Robot_basic *robot_);
64  static Dynamics *Instance();
65  virtual ~Dynamics(){}
66  void set_dof(Robot_basic *robot_);
67  short set_controller(const Control_Select & x);
68  short set_trajectory(const Trajectory_Select & x);
69  ReturnMatrix set_robot_on_first_point_of_splines();
70  void set_time_frame(const int nsteps);
71  void set_final_time(const double tf);
72  void reset_time();
74  void Runge_Kutta4();
75 
76  virtual void plot(){}
77 
78 // private:
79  ReturnMatrix xdot(const Matrix & xin);
80 
82  int ndof,
83  dof_fix,
84  nsteps;
85  double h,
86  h2,
87  time,
88  to,
89  tf,
90  tf_cont,
91  dt;
92  Matrix k1,
93  k2,
94  k3,
95  k4,
96  x,
97  xd;
99  qp,
100  qpp,
101  qd,
102  qpd,
103  qppd,
104  tau,
105  pd,
106  ppd,
107  pppd,
108  wd,
109  wpd;
114 
115  static Dynamics *instance;
116 };
117 
118 #ifdef use_namespace
119 }
120 #endif
121 
122 #endif
123 
Quaternion class definition.
Definition: quaternion.h:92
double to
Initial simulation time.
Definition: dynamics_sim.h:85
Header file for trajectory generation class.
Header file for Control_Select class definitions.
Quaternion quatd
Desired orientation express by a quaternion.
Definition: dynamics_sim.h:110
virtual void plot()
Virtual plot functions.
Definition: dynamics_sim.h:76
int nsteps
Numbers of iterations between.
Definition: dynamics_sim.h:82
void Runge_Kutta4_Real_time(ReturnMatrix(*xdot)(Real time, const Matrix &xin, bool &exit, bool &init), const Matrix &xo, Real to, Real tf, int nsteps)
Fixed step size fourth-order Runge-Kutta integrator.
Definition: utils.cpp:178
Robot_basic * robot
Pointer on Robot_basic class.
Definition: dynamics_sim.h:113
void Runge_Kutta4(ReturnMatrix(*xdot)(Real time, const Matrix &xin), const Matrix &xo, Real to, Real tf, int nsteps, RowVector &tout, Matrix &xout)
Fixed step size fourth-order Runge-Kutta integrator.
Definition: utils.cpp:232
Trajectory class selection.
Definition: trajectory.h:164
Utility header file.
ColumnVector wpd
Desired end effector cartesian angular acceleration.
Definition: dynamics_sim.h:98
Trajectory_Select path_select
Instance of Trajectory_Select class.
Definition: dynamics_sim.h:112
Virtual base robot class.
Definition: robot.h:216
Matrix xd
Statd vector derivative obtaint in xdot function.
Definition: dynamics_sim.h:92
The usual rectangular matrix.
Definition: newmat.h:625
Quaternion class.
bool first_pass_Kutta
First time in all Runge_Kutta4 functions.
Definition: dynamics_sim.h:81
static const char header_dynamics_sim_rcsid[]
RCS/CVS version.
Definition: dynamics_sim.h:41
Select controller class.
ReturnMatrix xdot(Real t, const Matrix &x)
Definition: demo.cpp:231
Column vector.
Definition: newmat.h:1008
virtual ~Dynamics()
Definition: dynamics_sim.h:65
Control_Select control
Instance of Control_Select class.
Definition: dynamics_sim.h:111
Dynamics simulation handling class.
Definition: dynamics_sim.h:60
static Dynamics * instance
Static pointer on Dynamics class.
Definition: dynamics_sim.h:115


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:44