Public Slots | Public Member Functions | Protected Slots | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
thormang3_demo::MainWindow Class Reference

Qt central, all operations relating to the view part here. More...

#include <main_window.hpp>

Inheritance diagram for thormang3_demo::MainWindow:
Inheritance graph
[legend]

Public Slots

void enableModule (QString mode_name)
 
void on_A0_button_fl_clicked (bool check)
 
void on_A0_button_get_step_clicked (bool check)
 
void on_A1_button_clear_step_clicked (bool check)
 
void on_A1_button_f_clicked (bool check)
 
void on_A2_button_fr_clicked (bool check)
 
void on_A2_button_go_walking_clicked (bool check)
 
void on_actionAbout_triggered ()
 
void on_B0_button_l_clicked (bool check)
 
void on_B1_button_stop_clicked (bool check)
 
void on_B2_button_r_clicked (bool check)
 
void on_button_assemble_lidar_clicked (bool check)
 
void on_button_balance_off_clicked (bool check)
 
void on_button_balance_on_clicked (bool check)
 
void on_button_clear_log_clicked (bool check)
 
void on_button_feedback_gain_apply_clicked (bool check)
 
void on_button_ft_air_clicked (bool check)
 
void on_button_ft_calc_clicked (bool check)
 
void on_button_ft_gnd_clicked (bool check)
 
void on_button_ft_save_clicked (bool check)
 
void on_button_grip_off_clicked (bool check)
 
void on_button_grip_on_clicked (bool check)
 
void on_button_init_pose_clicked (bool check)
 
void on_button_manipulation_demo_0_clicked (bool check)
 
void on_button_manipulation_demo_1_clicked (bool check)
 
void on_button_manipulation_demo_2_clicked (bool check)
 
void on_button_manipulation_demo_3_clicked (bool check)
 
void on_button_manipulation_demo_4_clicked (bool check)
 
void on_button_manipulation_demo_5_clicked (bool check)
 
void on_button_manipulation_demo_6_clicked (bool check)
 
void on_button_manipulation_demo_7_clicked (bool check)
 
void on_button_marker_clear_clicked ()
 
void on_button_marker_set_clicked ()
 
void on_button_motion_demo_0_clicked (bool check)
 
void on_button_motion_demo_1_clicked (bool check)
 
void on_button_walking_demo_0_clicked (bool check)
 
void on_button_walking_demo_1_clicked (bool check)
 
void on_button_walking_demo_2_clicked (bool check)
 
void on_button_walking_demo_3_clicked (bool check)
 
void on_button_walking_demo_4_clicked (bool check)
 
void on_button_walking_demo_5_clicked (bool check)
 
void on_button_walking_demo_6_clicked (bool check)
 
void on_button_walking_demo_7_clicked (bool check)
 
void on_C0_button_bl_clicked (bool check)
 
void on_C1_button_b_clicked (bool check)
 
void on_C2_button_br_clicked (bool check)
 
void on_currjoint_button_clicked (bool check)
 
void on_currpos_button_clicked (bool check)
 
void on_desjoint_button_clicked (bool check)
 
void on_despos_button_clicked (bool check)
 
void on_dSpinBox_marker_ori_p_valueChanged (double value)
 
void on_dSpinBox_marker_ori_r_valueChanged (double value)
 
void on_dSpinBox_marker_ori_y_valueChanged (double value)
 
void on_dSpinBox_marker_pos_x_valueChanged (double value)
 
void on_dSpinBox_marker_pos_y_valueChanged (double value)
 
void on_dSpinBox_marker_pos_z_valueChanged (double value)
 
void on_get_despos_button_clicked (bool check)
 
void on_head_center_button_clicked (bool check)
 
void on_inipose_button_clicked (bool check)
 
void on_tabWidget_control_currentChanged (int index)
 
void updateCurrJointSpinbox (double value)
 
void updateCurrOriSpinbox (double x, double y, double z, double w)
 
void updateCurrOriSpinbox (double r, double p, double y)
 
void updateCurrPosSpinbox (double x, double y, double z)
 
void updateHeadJointsAngle (double pan, double tilt)
 
void updateLoggingView ()
 
void updatePointPanel (const geometry_msgs::Point point)
 
void updatePosePanel (const geometry_msgs::Pose pose)
 
void updatePresentJointModule (std::vector< int > mode)
 

Public Member Functions

void closeEvent (QCloseEvent *event)
 
 MainWindow (int argc, char **argv, QWidget *parent=0)
 
void readSettings ()
 
void writeSettings ()
 
 ~MainWindow ()
 

Protected Slots

void playMotion (int motion_index)
 
void setHeadJointsAngle ()
 

Private Member Functions

void clearMarkerPanel ()
 
void getPointFromMarkerPanel (geometry_msgs::Point &current)
 
void getPoseFromMarkerPanel (geometry_msgs::Pose &current)
 
void initModeUnit ()
 
void initMotionUnit ()
 
void makeInteractiveMarker ()
 
Eigen::MatrixXd quaternion2rotation (const Eigen::Quaterniond &quaternion)
 
Eigen::Vector3d quaternion2rpy (const Eigen::Quaterniond &quaternion)
 
Eigen::Vector3d quaternion2rpy (const geometry_msgs::Quaternion &quaternion)
 
Eigen::Quaterniond rotation2quaternion (const Eigen::MatrixXd &rotation)
 
Eigen::Vector3d rotation2rpy (const Eigen::MatrixXd &rotation)
 
Eigen::MatrixXd rotationX (const double &angle)
 
Eigen::MatrixXd rotationY (const double &angle)
 
Eigen::MatrixXd rotationZ (const double &angle)
 
Eigen::Quaterniond rpy2quaternion (const Eigen::Vector3d &euler)
 
Eigen::Quaterniond rpy2quaternion (const double &roll, const double &pitch, const double &yaw)
 
Eigen::MatrixXd rpy2rotation (const double &roll, const double &pitch, const double &yaw)
 
void sendWalkingCommand (const std::string &command)
 
void setGripper (const double angle_deg, const double torque_limit, const std::string &arm_type)
 
void setHeadJointsAngle (double pan, double tilt)
 
void setPointToMarkerPanel (const geometry_msgs::Point &current)
 
void setPoseToMarkerPanel (const geometry_msgs::Pose &current)
 
void setUserShortcut ()
 
void updateInteractiveMarker ()
 
void updateModuleUI ()
 

Private Attributes

bool debug_print_
 
bool demo_mode_
 
bool is_updating_
 
std::map< std::string, QList< QWidget * > > module_ui_table_
 
QNodeThor3 qnode_thor3_
 
Ui::MainWindowDesign ui_
 

Static Private Attributes

static const double GRIPPER_OFF_ANGLE = 5
 
static const double GRIPPER_ON_ANGLE = 60
 
static const double GRIPPER_TORQUE_LIMIT = 250
 

Detailed Description

Qt central, all operations relating to the view part here.

Definition at line 43 of file main_window.hpp.

Constructor & Destructor Documentation

thormang3_demo::MainWindow::MainWindow ( int  argc,
char **  argv,
QWidget *  parent = 0 
)

Definition at line 41 of file main_window.cpp.

thormang3_demo::MainWindow::~MainWindow ( )

Definition at line 111 of file main_window.cpp.

Member Function Documentation

void thormang3_demo::MainWindow::clearMarkerPanel ( )
private

Definition at line 884 of file main_window.cpp.

void thormang3_demo::MainWindow::closeEvent ( QCloseEvent *  event)

Definition at line 1065 of file main_window.cpp.

void thormang3_demo::MainWindow::enableModule ( QString  mode_name)
slot

Definition at line 1046 of file main_window.cpp.

void thormang3_demo::MainWindow::getPointFromMarkerPanel ( geometry_msgs::Point current)
private

Definition at line 842 of file main_window.cpp.

void thormang3_demo::MainWindow::getPoseFromMarkerPanel ( geometry_msgs::Pose current)
private

Definition at line 812 of file main_window.cpp.

void thormang3_demo::MainWindow::initModeUnit ( )
private

Definition at line 907 of file main_window.cpp.

void thormang3_demo::MainWindow::initMotionUnit ( )
private

Definition at line 999 of file main_window.cpp.

void thormang3_demo::MainWindow::makeInteractiveMarker ( )
private

Definition at line 864 of file main_window.cpp.

void thormang3_demo::MainWindow::on_A0_button_fl_clicked ( bool  check)
slot

Definition at line 236 of file main_window.cpp.

void thormang3_demo::MainWindow::on_A0_button_get_step_clicked ( bool  check)
slot

Definition at line 294 of file main_window.cpp.

void thormang3_demo::MainWindow::on_A1_button_clear_step_clicked ( bool  check)
slot

Definition at line 319 of file main_window.cpp.

void thormang3_demo::MainWindow::on_A1_button_f_clicked ( bool  check)
slot

Definition at line 241 of file main_window.cpp.

void thormang3_demo::MainWindow::on_A2_button_fr_clicked ( bool  check)
slot

Definition at line 246 of file main_window.cpp.

void thormang3_demo::MainWindow::on_A2_button_go_walking_clicked ( bool  check)
slot

Definition at line 327 of file main_window.cpp.

void thormang3_demo::MainWindow::on_actionAbout_triggered ( )
slot

Definition at line 898 of file main_window.cpp.

void thormang3_demo::MainWindow::on_B0_button_l_clicked ( bool  check)
slot

Definition at line 251 of file main_window.cpp.

void thormang3_demo::MainWindow::on_B1_button_stop_clicked ( bool  check)
slot

Definition at line 256 of file main_window.cpp.

void thormang3_demo::MainWindow::on_B2_button_r_clicked ( bool  check)
slot

Definition at line 261 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_assemble_lidar_clicked ( bool  check)
slot

Definition at line 119 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_balance_off_clicked ( bool  check)
slot

Definition at line 284 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_balance_on_clicked ( bool  check)
slot

Definition at line 279 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_clear_log_clicked ( bool  check)
slot

Definition at line 123 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_feedback_gain_apply_clicked ( bool  check)
slot

Definition at line 289 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_ft_air_clicked ( bool  check)
slot

Definition at line 132 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_ft_calc_clicked ( bool  check)
slot

Definition at line 140 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_ft_gnd_clicked ( bool  check)
slot

Definition at line 136 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_ft_save_clicked ( bool  check)
slot

Definition at line 145 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_grip_off_clicked ( bool  check)
slot

Definition at line 231 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_grip_on_clicked ( bool  check)
slot

Definition at line 226 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_init_pose_clicked ( bool  check)
slot

Definition at line 127 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_0_clicked ( bool  check)
slot

Definition at line 384 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_1_clicked ( bool  check)
slot

Definition at line 390 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_2_clicked ( bool  check)
slot

Definition at line 397 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_3_clicked ( bool  check)
slot

Definition at line 403 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_4_clicked ( bool  check)
slot

Definition at line 415 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_5_clicked ( bool  check)
slot

Definition at line 434 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_6_clicked ( bool  check)
slot

Definition at line 467 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_manipulation_demo_7_clicked ( bool  check)
slot

Definition at line 475 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_marker_clear_clicked ( )
slot

Definition at line 376 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_marker_set_clicked ( )
slot

Definition at line 371 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_motion_demo_0_clicked ( bool  check)
slot

Definition at line 579 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_motion_demo_1_clicked ( bool  check)
slot

Definition at line 585 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_0_clicked ( bool  check)
slot

Definition at line 486 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_1_clicked ( bool  check)
slot

Definition at line 492 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_2_clicked ( bool  check)
slot

Definition at line 504 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_3_clicked ( bool  check)
slot

Definition at line 516 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_4_clicked ( bool  check)
slot

Definition at line 522 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_5_clicked ( bool  check)
slot

Definition at line 546 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_6_clicked ( bool  check)
slot

Definition at line 556 of file main_window.cpp.

void thormang3_demo::MainWindow::on_button_walking_demo_7_clicked ( bool  check)
slot

Definition at line 568 of file main_window.cpp.

void thormang3_demo::MainWindow::on_C0_button_bl_clicked ( bool  check)
slot

Definition at line 266 of file main_window.cpp.

void thormang3_demo::MainWindow::on_C1_button_b_clicked ( bool  check)
slot

Definition at line 270 of file main_window.cpp.

void thormang3_demo::MainWindow::on_C2_button_br_clicked ( bool  check)
slot

Definition at line 275 of file main_window.cpp.

void thormang3_demo::MainWindow::on_currjoint_button_clicked ( bool  check)
slot

Definition at line 170 of file main_window.cpp.

void thormang3_demo::MainWindow::on_currpos_button_clicked ( bool  check)
slot

Definition at line 196 of file main_window.cpp.

void thormang3_demo::MainWindow::on_desjoint_button_clicked ( bool  check)
slot

Definition at line 175 of file main_window.cpp.

void thormang3_demo::MainWindow::on_despos_button_clicked ( bool  check)
slot

Definition at line 201 of file main_window.cpp.

void thormang3_demo::MainWindow::on_dSpinBox_marker_ori_p_valueChanged ( double  value)
slot

Definition at line 361 of file main_window.cpp.

void thormang3_demo::MainWindow::on_dSpinBox_marker_ori_r_valueChanged ( double  value)
slot

Definition at line 356 of file main_window.cpp.

void thormang3_demo::MainWindow::on_dSpinBox_marker_ori_y_valueChanged ( double  value)
slot

Definition at line 366 of file main_window.cpp.

void thormang3_demo::MainWindow::on_dSpinBox_marker_pos_x_valueChanged ( double  value)
slot

Definition at line 341 of file main_window.cpp.

void thormang3_demo::MainWindow::on_dSpinBox_marker_pos_y_valueChanged ( double  value)
slot

Definition at line 346 of file main_window.cpp.

void thormang3_demo::MainWindow::on_dSpinBox_marker_pos_z_valueChanged ( double  value)
slot

Definition at line 351 of file main_window.cpp.

void thormang3_demo::MainWindow::on_get_despos_button_clicked ( bool  check)
slot

Definition at line 185 of file main_window.cpp.

void thormang3_demo::MainWindow::on_head_center_button_clicked ( bool  check)
slot

Definition at line 335 of file main_window.cpp.

void thormang3_demo::MainWindow::on_inipose_button_clicked ( bool  check)
slot

Definition at line 162 of file main_window.cpp.

void thormang3_demo::MainWindow::on_tabWidget_control_currentChanged ( int  index)
slot

Definition at line 151 of file main_window.cpp.

void thormang3_demo::MainWindow::playMotion ( int  motion_index)
protectedslot

Definition at line 728 of file main_window.cpp.

Eigen::MatrixXd thormang3_demo::MainWindow::quaternion2rotation ( const Eigen::Quaterniond &  quaternion)
private

Definition at line 1141 of file main_window.cpp.

Eigen::Vector3d thormang3_demo::MainWindow::quaternion2rpy ( const Eigen::Quaterniond &  quaternion)
private

Definition at line 1124 of file main_window.cpp.

Eigen::Vector3d thormang3_demo::MainWindow::quaternion2rpy ( const geometry_msgs::Quaternion &  quaternion)
private

Definition at line 1131 of file main_window.cpp.

void thormang3_demo::MainWindow::readSettings ( )

Definition at line 1051 of file main_window.cpp.

Eigen::Quaterniond thormang3_demo::MainWindow::rotation2quaternion ( const Eigen::MatrixXd &  rotation)
private

Definition at line 1112 of file main_window.cpp.

Eigen::Vector3d thormang3_demo::MainWindow::rotation2rpy ( const Eigen::MatrixXd &  rotation)
private

Definition at line 1075 of file main_window.cpp.

Eigen::MatrixXd thormang3_demo::MainWindow::rotationX ( const double &  angle)
private

Definition at line 1148 of file main_window.cpp.

Eigen::MatrixXd thormang3_demo::MainWindow::rotationY ( const double &  angle)
private

Definition at line 1157 of file main_window.cpp.

Eigen::MatrixXd thormang3_demo::MainWindow::rotationZ ( const double &  angle)
private

Definition at line 1166 of file main_window.cpp.

Eigen::Quaterniond thormang3_demo::MainWindow::rpy2quaternion ( const Eigen::Vector3d &  euler)
private

Definition at line 1093 of file main_window.cpp.

Eigen::Quaterniond thormang3_demo::MainWindow::rpy2quaternion ( const double &  roll,
const double &  pitch,
const double &  yaw 
)
private

Definition at line 1098 of file main_window.cpp.

Eigen::MatrixXd thormang3_demo::MainWindow::rpy2rotation ( const double &  roll,
const double &  pitch,
const double &  yaw 
)
private

Definition at line 1086 of file main_window.cpp.

void thormang3_demo::MainWindow::sendWalkingCommand ( const std::string &  command)
private

Definition at line 776 of file main_window.cpp.

void thormang3_demo::MainWindow::setGripper ( const double  angle_deg,
const double  torque_limit,
const std::string &  arm_type 
)
private

Definition at line 765 of file main_window.cpp.

void thormang3_demo::MainWindow::setHeadJointsAngle ( )
protectedslot

Definition at line 715 of file main_window.cpp.

void thormang3_demo::MainWindow::setHeadJointsAngle ( double  pan,
double  tilt 
)
private

Definition at line 723 of file main_window.cpp.

void thormang3_demo::MainWindow::setPointToMarkerPanel ( const geometry_msgs::Point current)
private

Definition at line 850 of file main_window.cpp.

void thormang3_demo::MainWindow::setPoseToMarkerPanel ( const geometry_msgs::Pose current)
private

Definition at line 827 of file main_window.cpp.

void thormang3_demo::MainWindow::setUserShortcut ( )
private

Definition at line 601 of file main_window.cpp.

void thormang3_demo::MainWindow::updateCurrJointSpinbox ( double  value)
slot

Definition at line 736 of file main_window.cpp.

void thormang3_demo::MainWindow::updateCurrOriSpinbox ( double  x,
double  y,
double  z,
double  w 
)
slot

Definition at line 748 of file main_window.cpp.

void thormang3_demo::MainWindow::updateCurrOriSpinbox ( double  r,
double  p,
double  y 
)
slot

Definition at line 758 of file main_window.cpp.

void thormang3_demo::MainWindow::updateCurrPosSpinbox ( double  x,
double  y,
double  z 
)
slot

Definition at line 741 of file main_window.cpp.

void thormang3_demo::MainWindow::updateHeadJointsAngle ( double  pan,
double  tilt 
)
slot

Definition at line 696 of file main_window.cpp.

void thormang3_demo::MainWindow::updateInteractiveMarker ( )
private

Definition at line 873 of file main_window.cpp.

void thormang3_demo::MainWindow::updateLoggingView ( )
slot

Definition at line 595 of file main_window.cpp.

void thormang3_demo::MainWindow::updateModuleUI ( )
private

Definition at line 671 of file main_window.cpp.

void thormang3_demo::MainWindow::updatePointPanel ( const geometry_msgs::Point  point)
slot

Definition at line 791 of file main_window.cpp.

void thormang3_demo::MainWindow::updatePosePanel ( const geometry_msgs::Pose  pose)
slot

Definition at line 802 of file main_window.cpp.

void thormang3_demo::MainWindow::updatePresentJointModule ( std::vector< int >  mode)
slot

Definition at line 640 of file main_window.cpp.

void thormang3_demo::MainWindow::writeSettings ( )

Definition at line 1058 of file main_window.cpp.

Member Data Documentation

bool thormang3_demo::MainWindow::debug_print_
private

Definition at line 200 of file main_window.hpp.

bool thormang3_demo::MainWindow::demo_mode_
private

Definition at line 201 of file main_window.hpp.

const double thormang3_demo::MainWindow::GRIPPER_OFF_ANGLE = 5
staticprivate

Definition at line 164 of file main_window.hpp.

const double thormang3_demo::MainWindow::GRIPPER_ON_ANGLE = 60
staticprivate

Definition at line 163 of file main_window.hpp.

const double thormang3_demo::MainWindow::GRIPPER_TORQUE_LIMIT = 250
staticprivate

Definition at line 165 of file main_window.hpp.

bool thormang3_demo::MainWindow::is_updating_
private

Definition at line 202 of file main_window.hpp.

std::map<std::string, QList<QWidget *> > thormang3_demo::MainWindow::module_ui_table_
private

Definition at line 203 of file main_window.hpp.

QNodeThor3 thormang3_demo::MainWindow::qnode_thor3_
private

Definition at line 199 of file main_window.hpp.

Ui::MainWindowDesign thormang3_demo::MainWindow::ui_
private

Definition at line 198 of file main_window.hpp.


The documentation for this class was generated from the following files:


thormang3_demo
Author(s): Kayman
autogenerated on Mon Jun 10 2019 15:38:34