Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00040
00041 static const char rcsid[] = "$Id: demo_2dof_pd.cpp,v 1.2 2006/05/16 16:27:43 gourdeau Exp $";
00042
00043 #include "gnugraph.h"
00044 #include "controller.h"
00045 #include "control_select.h"
00046 #include "dynamics_sim.h"
00047 #include "robot.h"
00048 #include "trajectory.h"
00049
00050 #ifdef use_namespace
00051 using namespace ROBOOP;
00052 #endif
00053
00063 class New_dynamics: public Dynamics
00064 {
00065 public:
00066 New_dynamics(Robot_basic *robot_);
00067 virtual void plot();
00068
00069 Robot_basic *robot;
00070 bool first_pass_plot;
00071 RowVector tout;
00072 Matrix xout;
00073 int i;
00074 };
00075
00080 New_dynamics::New_dynamics(Robot_basic *robot_): Dynamics(robot_)
00081 {
00082 robot = robot_;
00083 first_pass_plot = true;
00084 i = 1;
00085 }
00086
00094 void New_dynamics::plot()
00095 {
00096 if(first_pass_plot)
00097 {
00098 xout = Matrix(x.Nrows(),(int)(nsteps*(tf_cont-to)+1)*x.Ncols());
00099 xout.SubMatrix(1,x.Nrows(),1,x.Ncols()) = x;
00100 tout = RowVector((int)(nsteps*(tf_cont-to)+1));
00101 tout(1) = to;
00102 i = 0;
00103 first_pass_plot = false;
00104 }
00105
00106 if(robot)
00107 {
00108 tout(i+1) = time;
00109 xout.SubMatrix(1,x.Nrows(),i*x.Ncols()+1,(i+1)*x.Ncols()) = x;
00110 i++;
00111 }
00112 }
00113
00114
00115 int main()
00116 {
00117
00118 Robot robot("conf/rr_dh.conf", "rr_dh");
00119
00120 Trajectory_Select path("conf/q_2dof.dat");
00121 Control_Select control("conf/pd_2dof.conf");
00122
00123 New_dynamics dynamics(&robot);
00124
00125 dynamics.set_controller(control);
00126 dynamics.set_trajectory(path);
00127 dynamics.set_time_frame(500);
00128
00129 dynamics.Runge_Kutta4();
00130
00131 set_plot2d("Robot joints position", "time (sec)", "q(i) (rad)", "q", DATAPOINTS,
00132 dynamics.tout, dynamics.xout, 1, 2);
00133
00134 return(0);
00135 }
00136
00137