#include <output_recorder.h>
Public Member Functions | |
double | calculateLS (std::vector< double > *vec_out, std::vector< double > *vec_in, int model_order, double &a1, double &a2, double &a3, double &b1, double &b2, double &b3) |
void | euler (std::vector< double > *out, double in, double dt) |
void | fillDataVectors (double x_dot_lin_in, double x_dot_lin_out, double y_dot_lin_in, double y_dot_lin_out, double z_dot_lin_in, double z_dot_lin_out, double x_dot_rot_in, double x_dot_rot_out, double y_dot_rot_in, double y_dot_rot_out, double z_dot_rot_in, double z_dot_rot_out, double x_lin_out, double y_lin_out, double z_lin_out, double x_rot_out, double y_rot_out, double z_rot_out) |
geometry_msgs::Pose | getEndeffectorPose () |
bool | initialize () |
void | jointstateCallback (const sensor_msgs::JointState::ConstPtr &msg) |
void | pseudoInverse (const Eigen::MatrixXd &matrix, Eigen::MatrixXd &matrix_inv, double tolerance) |
void | quit (int sig) |
void | run () |
void | stepResponsePlot (std::string file_name, std::vector< double > *in, std::vector< double > *x_lin_out, std::vector< double > *y_lin_out, std::vector< double > *z_lin_out, std::vector< double > *x_rot_out, std::vector< double > *y_rot_out, std::vector< double > *z_rot_out) |
void | stopRecording () |
void | twistCallback (const geometry_msgs::TwistStamped::ConstPtr &msg) |
void | writeToMFile (std::string file_name, std::vector< double > *dot_in, std::vector< double > *dot_out, std::vector< double > *pos_out, std::vector< double > *dot_integrated) |
Private Attributes | |
char | c |
For Keyboard commands. | |
KDL::Chain | chain_ |
KDL Conversion. | |
std::string | chain_base_link_ |
std::string | chain_tip_link_ |
unsigned int | dof_ |
double | dt_ |
Euler Integration. | |
bool | finished_recording_ |
KDL::ChainFkSolverVel_recursive * | jntToCartSolver_vel_ |
std::vector< std::string > | joints_ |
ros::Subscriber | jointstate_sub_ |
int | kfd |
KDL::JntArray | last_q_ |
KDL::JntArray | last_q_dot_ |
tf::TransformListener | listener_ |
Transform Listener. | |
ros::NodeHandle | nh_ |
std::string | output_file_path_ |
double | q_x_lin_out |
double | q_y_lin_out |
double | q_z_lin_out |
struct termios cooked | raw |
bool | start_ |
std::vector< double > | time_vec_ |
ros::Subscriber | twist_sub_ |
KDL::Vector | vector_rot_ |
KDL::Vector | vector_vel_ |
double | x_dot_lin_in_ |
std::vector< double > | x_dot_lin_vec_in_ |
Inputs. | |
std::vector< double > | x_dot_lin_vec_out_ |
Outputs. | |
double | x_dot_rot_in_ |
std::vector< double > | x_dot_rot_vec_in_ |
std::vector< double > | x_dot_rot_vec_out_ |
std::vector< double > | x_lin_vec_out_ |
std::vector< double > | x_rot_vec_out_ |
double | y_dot_lin_in_ |
std::vector< double > | y_dot_lin_vec_in_ |
std::vector< double > | y_dot_lin_vec_out_ |
double | y_dot_rot_in_ |
std::vector< double > | y_dot_rot_vec_in_ |
std::vector< double > | y_dot_rot_vec_out_ |
std::vector< double > | y_lin_vec_out_ |
std::vector< double > | y_rot_vec_out_ |
double | z_dot_lin_in_ |
std::vector< double > | z_dot_lin_vec_in_ |
std::vector< double > | z_dot_lin_vec_out_ |
double | z_dot_rot_in_ |
std::vector< double > | z_dot_rot_vec_in_ |
std::vector< double > | z_dot_rot_vec_out_ |
std::vector< double > | z_lin_vec_out_ |
std::vector< double > | z_rot_vec_out_ |
Definition at line 50 of file output_recorder.h.
double OutputRecorder::calculateLS | ( | std::vector< double > * | vec_out, |
std::vector< double > * | vec_in, | ||
int | model_order, | ||
double & | a1, | ||
double & | a2, | ||
double & | a3, | ||
double & | b1, | ||
double & | b2, | ||
double & | b3 | ||
) |
System 1. Ordnung
System 2. Ordnung
System 3. Ordnung
'double' machine precision http://freemat.sourceforge.net/help/constants_eps.html
Definition at line 344 of file output_recorder.cpp.
void OutputRecorder::euler | ( | std::vector< double > * | out, |
double | in, | ||
double | dt | ||
) |
Definition at line 485 of file output_recorder.cpp.
void OutputRecorder::fillDataVectors | ( | double | x_dot_lin_in, |
double | x_dot_lin_out, | ||
double | y_dot_lin_in, | ||
double | y_dot_lin_out, | ||
double | z_dot_lin_in, | ||
double | z_dot_lin_out, | ||
double | x_dot_rot_in, | ||
double | x_dot_rot_out, | ||
double | y_dot_rot_in, | ||
double | y_dot_rot_out, | ||
double | z_dot_rot_in, | ||
double | z_dot_rot_out, | ||
double | x_lin_out, | ||
double | y_lin_out, | ||
double | z_lin_out, | ||
double | x_rot_out, | ||
double | y_rot_out, | ||
double | z_rot_out | ||
) |
lin velocity
rot velocity
lin position
rot position
Definition at line 497 of file output_recorder.cpp.
Definition at line 317 of file output_recorder.cpp.
bool OutputRecorder::initialize | ( | ) |
parse robot_description and generate KDL chains
initialize variables and current joint values and velocities
Definition at line 32 of file output_recorder.cpp.
void OutputRecorder::jointstateCallback | ( | const sensor_msgs::JointState::ConstPtr & | msg | ) |
Definition at line 257 of file output_recorder.cpp.
void OutputRecorder::pseudoInverse | ( | const Eigen::MatrixXd & | matrix, |
Eigen::MatrixXd & | matrix_inv, | ||
double | tolerance | ||
) |
Definition at line 460 of file output_recorder.cpp.
void OutputRecorder::quit | ( | int | sig | ) |
Definition at line 251 of file output_recorder.cpp.
void OutputRecorder::run | ( | ) |
Ist Position
Sollgeschwindigkeit
Generate Octave Files
Velocity Stepresponse
Position Stepresponse
Definition at line 96 of file output_recorder.cpp.
void OutputRecorder::stepResponsePlot | ( | std::string | file_name, |
std::vector< double > * | in, | ||
std::vector< double > * | x_lin_out, | ||
std::vector< double > * | y_lin_out, | ||
std::vector< double > * | z_lin_out, | ||
std::vector< double > * | x_rot_out, | ||
std::vector< double > * | y_rot_out, | ||
std::vector< double > * | z_rot_out | ||
) |
Get the vectors and write them to .m file-----------------------
Definition at line 532 of file output_recorder.cpp.
void OutputRecorder::stopRecording | ( | ) |
Definition at line 224 of file output_recorder.cpp.
void OutputRecorder::twistCallback | ( | const geometry_msgs::TwistStamped::ConstPtr & | msg | ) |
Definition at line 305 of file output_recorder.cpp.
void OutputRecorder::writeToMFile | ( | std::string | file_name, |
std::vector< double > * | dot_in, | ||
std::vector< double > * | dot_out, | ||
std::vector< double > * | pos_out, | ||
std::vector< double > * | dot_integrated | ||
) |
Get the vectors and write them to .m file
-----------------------------------------------------------------
Generate the time vector based on average sample time
-----------------------------------------------------------------
Generate Velocity Models----------------------------------------
1. Order
2. Order
3. Order
Errorplot to identify model order-------------------------------
First order
Second order
Third order
Definition at line 606 of file output_recorder.cpp.
char OutputRecorder::c [private] |
For Keyboard commands.
Definition at line 125 of file output_recorder.h.
KDL::Chain OutputRecorder::chain_ [private] |
KDL Conversion.
Definition at line 86 of file output_recorder.h.
std::string OutputRecorder::chain_base_link_ [private] |
Definition at line 88 of file output_recorder.h.
std::string OutputRecorder::chain_tip_link_ [private] |
Definition at line 89 of file output_recorder.h.
unsigned int OutputRecorder::dof_ [private] |
Definition at line 94 of file output_recorder.h.
double OutputRecorder::dt_ [private] |
Euler Integration.
Definition at line 118 of file output_recorder.h.
bool OutputRecorder::finished_recording_ [private] |
Definition at line 121 of file output_recorder.h.
Definition at line 93 of file output_recorder.h.
std::vector<std::string> OutputRecorder::joints_ [private] |
Definition at line 92 of file output_recorder.h.
Definition at line 83 of file output_recorder.h.
int OutputRecorder::kfd [private] |
Definition at line 126 of file output_recorder.h.
KDL::JntArray OutputRecorder::last_q_ [private] |
Definition at line 90 of file output_recorder.h.
KDL::JntArray OutputRecorder::last_q_dot_ [private] |
Definition at line 91 of file output_recorder.h.
Transform Listener.
Definition at line 115 of file output_recorder.h.
ros::NodeHandle OutputRecorder::nh_ [private] |
Definition at line 81 of file output_recorder.h.
std::string OutputRecorder::output_file_path_ [private] |
Definition at line 87 of file output_recorder.h.
double OutputRecorder::q_x_lin_out [private] |
Definition at line 105 of file output_recorder.h.
double OutputRecorder::q_y_lin_out [private] |
Definition at line 105 of file output_recorder.h.
double OutputRecorder::q_z_lin_out [private] |
Definition at line 105 of file output_recorder.h.
struct termios cooked OutputRecorder::raw [private] |
Definition at line 127 of file output_recorder.h.
bool OutputRecorder::start_ [private] |
Definition at line 120 of file output_recorder.h.
std::vector<double> OutputRecorder::time_vec_ [private] |
Definition at line 122 of file output_recorder.h.
ros::Subscriber OutputRecorder::twist_sub_ [private] |
Definition at line 82 of file output_recorder.h.
KDL::Vector OutputRecorder::vector_rot_ [private] |
Definition at line 95 of file output_recorder.h.
KDL::Vector OutputRecorder::vector_vel_ [private] |
Definition at line 95 of file output_recorder.h.
double OutputRecorder::x_dot_lin_in_ [private] |
Definition at line 111 of file output_recorder.h.
std::vector<double> OutputRecorder::x_dot_lin_vec_in_ [private] |
Inputs.
Definition at line 108 of file output_recorder.h.
std::vector<double> OutputRecorder::x_dot_lin_vec_out_ [private] |
Outputs.
Definition at line 99 of file output_recorder.h.
double OutputRecorder::x_dot_rot_in_ [private] |
Definition at line 112 of file output_recorder.h.
std::vector<double> OutputRecorder::x_dot_rot_vec_in_ [private] |
Definition at line 109 of file output_recorder.h.
std::vector<double> OutputRecorder::x_dot_rot_vec_out_ [private] |
Definition at line 100 of file output_recorder.h.
std::vector<double> OutputRecorder::x_lin_vec_out_ [private] |
Definition at line 103 of file output_recorder.h.
std::vector<double> OutputRecorder::x_rot_vec_out_ [private] |
Definition at line 104 of file output_recorder.h.
double OutputRecorder::y_dot_lin_in_ [private] |
Definition at line 111 of file output_recorder.h.
std::vector<double> OutputRecorder::y_dot_lin_vec_in_ [private] |
Definition at line 108 of file output_recorder.h.
std::vector<double> OutputRecorder::y_dot_lin_vec_out_ [private] |
Definition at line 99 of file output_recorder.h.
double OutputRecorder::y_dot_rot_in_ [private] |
Definition at line 112 of file output_recorder.h.
std::vector<double> OutputRecorder::y_dot_rot_vec_in_ [private] |
Definition at line 109 of file output_recorder.h.
std::vector<double> OutputRecorder::y_dot_rot_vec_out_ [private] |
Definition at line 100 of file output_recorder.h.
std::vector<double> OutputRecorder::y_lin_vec_out_ [private] |
Definition at line 103 of file output_recorder.h.
std::vector<double> OutputRecorder::y_rot_vec_out_ [private] |
Definition at line 104 of file output_recorder.h.
double OutputRecorder::z_dot_lin_in_ [private] |
Definition at line 111 of file output_recorder.h.
std::vector<double> OutputRecorder::z_dot_lin_vec_in_ [private] |
Definition at line 108 of file output_recorder.h.
std::vector<double> OutputRecorder::z_dot_lin_vec_out_ [private] |
Definition at line 99 of file output_recorder.h.
double OutputRecorder::z_dot_rot_in_ [private] |
Definition at line 112 of file output_recorder.h.
std::vector<double> OutputRecorder::z_dot_rot_vec_in_ [private] |
Definition at line 109 of file output_recorder.h.
std::vector<double> OutputRecorder::z_dot_rot_vec_out_ [private] |
Definition at line 100 of file output_recorder.h.
std::vector<double> OutputRecorder::z_lin_vec_out_ [private] |
Definition at line 103 of file output_recorder.h.
std::vector<double> OutputRecorder::z_rot_vec_out_ [private] |
Definition at line 104 of file output_recorder.h.