24 #ifndef manipulator_h_gui_MAIN_WINDOW_H 25 #define manipulator_h_gui_MAIN_WINDOW_H 34 #include <QtGui/QMainWindow> 35 #include "ui_main_window.h" 56 MainWindow(
int argc,
char** argv, QWidget *parent = 0);
64 Eigen::MatrixXd
rotationX(
double angle );
65 Eigen::MatrixXd
rotationY(
double angle );
66 Eigen::MatrixXd
rotationZ(
double angle );
68 Eigen::MatrixXd
rotation2rpy( Eigen::MatrixXd rotation );
69 Eigen::MatrixXd
rpy2rotation(
double roll,
double pitch,
double yaw );
71 Eigen::Quaterniond
rpy2quaternion(
double roll,
double pitch,
double yaw );
101 Ui::MainWindowDesign
ui;
111 #endif // manipulator_h_gui_MAIN_WINDOW_H QList< QAbstractSpinBox * > joint_spinbox
Eigen::Quaterniond rotation2quaternion(Eigen::MatrixXd rotation)
void on_curr_pos_button_clicked(bool check)
Eigen::MatrixXd rotation2rpy(Eigen::MatrixXd rotation)
Eigen::MatrixXd quaternion2rpy(Eigen::Quaterniond quaternion)
void closeEvent(QCloseEvent *event)
MainWindow(int argc, char **argv, QWidget *parent=0)
void on_actionAbout_triggered()
void on_des_pos_button_clicked(bool check)
void on_curr_joint_button_clicked(bool check)
Eigen::MatrixXd rotationX(double angle)
Qt central, all operations relating to the view part here.
Eigen::Quaterniond rpy2quaternion(double roll, double pitch, double yaw)
std::vector< std::string > joint_name
Eigen::MatrixXd rotationZ(double angle)
void on_set_mode_button_clicked(bool check)
void updateCurrJointPoseSpinbox(manipulator_h_base_module_msgs::JointPose msg)
Eigen::MatrixXd quaternion2rotation(Eigen::Quaterniond quaternion)
void on_ini_pose_button_clicked(bool check)
void updateCurrKinematicsPoseSpinbox(manipulator_h_base_module_msgs::KinematicsPose msg)
void on_des_joint_button_clicked(bool check)
Eigen::MatrixXd rpy2rotation(double roll, double pitch, double yaw)
Eigen::MatrixXd rotationY(double angle)