Public Slots | Signals | Public Member Functions | Private Types | Private Slots | Private Attributes | List of all members
moveit_rviz_plugin::ControlTabWidget Class Reference

#include <handeye_control_widget.h>

Inheritance diagram for moveit_rviz_plugin::ControlTabWidget:
Inheritance graph
[legend]

Public Slots

void updateFrameNames (std::map< std::string, std::string > names)
 
void UpdateSensorMountType (int index)
 

Signals

void sensorPoseUpdate (double x, double y, double z, double rx, double ry, double rz)
 

Public Member Functions

void addPoseSampleToTreeView (const geometry_msgs::TransformStamped &camera_to_object_tf, const geometry_msgs::TransformStamped &base_to_eef_tf, int id)
 
bool checkJointStates ()
 
void computeExecution ()
 
void computePlan ()
 
 ControlTabWidget (HandEyeCalibrationDisplay *pdisplay, QWidget *parent=Q_NULLPTR)
 
bool createSolverInstance (const std::string &plugin_name)
 
void fillPlanningGroupNameComboBox ()
 
void fillSolverTypes (const std::vector< std::string > &plugins)
 
bool frameNamesEmpty ()
 
bool loadSolverPlugin (std::vector< std::string > &plugins)
 
void loadWidget (const rviz::Config &config)
 
std::string parseSolverName (const std::string &solver_name, char delimiter)
 
void saveWidget (rviz::Config &config)
 
void setTFTool (rviz_visual_tools::TFVisualToolsPtr &tf_pub)
 
bool solveCameraRobotPose ()
 
bool takeTransformSamples ()
 
 ~ControlTabWidget ()
 

Private Types

enum  PLANNING_RESULT {
  SUCCESS = 0, FAILURE_NO_JOINT_STATE = 1, FAILURE_INVALID_JOINT_STATE = 2, FAILURE_NO_PSM = 3,
  FAILURE_NO_MOVE_GROUP = 4, FAILURE_WRONG_MOVE_GROUP = 5, FAILURE_PLAN_FAILED = 6
}
 

Private Slots

void autoExecuteBtnClicked (bool clicked)
 
void autoPlanBtnClicked (bool clicked)
 
void autoSkipBtnClicked (bool clicked)
 
void clearSamplesBtnClicked (bool clicked)
 
void executeFinished ()
 
void loadJointStateBtnClicked (bool clicked)
 
void loadSamplesBtnClicked (bool clicked)
 
void planFinished ()
 
void planningGroupNameChanged (const QString &text)
 
void planningGroupNamespaceChanged ()
 
void saveCameraPoseBtnClicked (bool clicked)
 
void saveJointStateBtnClicked (bool clicked)
 
void saveSamplesBtnClicked (bool clicked)
 
void setGroupName (const std::string &group_name)
 
void solveBtnClicked (bool clicked)
 
void takeSampleBtnClicked (bool clicked)
 

Private Attributes

QPushButton * auto_execute_btn_
 
QPushButton * auto_plan_btn_
 
ProgressBarWidgetauto_progress_
 
QPushButton * auto_skip_btn_
 
bool auto_started_
 
HandEyeCalibrationDisplaycalibration_display_
 
QComboBox * calibration_solver_
 
Eigen::Isometry3d camera_robot_pose_
 
moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_
 
std::vector< Eigen::Isometry3d > effector_wrt_world_
 
QFutureWatcher< void > * execution_watcher_
 
std::map< std::string, std::string > frame_names_
 
std::string from_frame_tag_
 
QComboBox * group_name_
 
std::vector< std::string > joint_names_
 
std::vector< std::vector< double > > joint_states_
 
QPushButton * load_joint_state_btn_
 
QPushButton * load_samples_btn_
 
moveit::planning_interface::MoveGroupInterfacePtr move_group_
 
ros::NodeHandle nh_
 
std::vector< Eigen::Isometry3d > object_wrt_sensor_
 
QFutureWatcher< void > * plan_watcher_
 
PLANNING_RESULT planning_res_
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
QLabel * reprojection_error_label_
 
QPushButton * reset_sample_btn_
 
QTreeView * sample_tree_view_
 
QPushButton * save_camera_pose_btn_
 
QPushButton * save_joint_state_btn_
 
QPushButton * save_samples_btn_
 
mhc::SensorMountType sensor_mount_type_
 
QPushButton * solve_btn_
 
pluginlib::UniquePtr< moveit_handeye_calibration::HandEyeSolverBasesolver_
 
std::unique_ptr< pluginlib::ClassLoader< moveit_handeye_calibration::HandEyeSolverBase > > solver_plugins_loader_
 
QPushButton * take_sample_btn_
 
std::shared_ptr< tf2_ros::Buffertf_buffer_
 
tf2_ros::TransformListener tf_listener_
 
rviz_visual_tools::TFVisualToolsPtr tf_tools_
 
QStandardItemModel * tree_view_model_
 

Detailed Description

Definition at line 133 of file handeye_control_widget.h.

Member Enumeration Documentation

◆ PLANNING_RESULT

Enumerator
SUCCESS 
FAILURE_NO_JOINT_STATE 
FAILURE_INVALID_JOINT_STATE 
FAILURE_NO_PSM 
FAILURE_NO_MOVE_GROUP 
FAILURE_WRONG_MOVE_GROUP 
FAILURE_PLAN_FAILED 

Definition at line 137 of file handeye_control_widget.h.

Constructor & Destructor Documentation

◆ ControlTabWidget()

moveit_rviz_plugin::ControlTabWidget::ControlTabWidget ( HandEyeCalibrationDisplay pdisplay,
QWidget *  parent = Q_NULLPTR 
)
explicit

Definition at line 130 of file handeye_control_widget.cpp.

◆ ~ControlTabWidget()

moveit_rviz_plugin::ControlTabWidget::~ControlTabWidget ( )
inline

Definition at line 150 of file handeye_control_widget.h.

Member Function Documentation

◆ addPoseSampleToTreeView()

void moveit_rviz_plugin::ControlTabWidget::addPoseSampleToTreeView ( const geometry_msgs::TransformStamped &  camera_to_object_tf,
const geometry_msgs::TransformStamped &  base_to_eef_tf,
int  id 
)

Definition at line 529 of file handeye_control_widget.cpp.

◆ autoExecuteBtnClicked

void moveit_rviz_plugin::ControlTabWidget::autoExecuteBtnClicked ( bool  clicked)
privateslot

Definition at line 1034 of file handeye_control_widget.cpp.

◆ autoPlanBtnClicked

void moveit_rviz_plugin::ControlTabWidget::autoPlanBtnClicked ( bool  clicked)
privateslot

Definition at line 966 of file handeye_control_widget.cpp.

◆ autoSkipBtnClicked

void moveit_rviz_plugin::ControlTabWidget::autoSkipBtnClicked ( bool  clicked)
privateslot

Definition at line 1108 of file handeye_control_widget.cpp.

◆ checkJointStates()

bool moveit_rviz_plugin::ControlTabWidget::checkJointStates ( )

Definition at line 512 of file handeye_control_widget.cpp.

◆ clearSamplesBtnClicked

void moveit_rviz_plugin::ControlTabWidget::clearSamplesBtnClicked ( bool  clicked)
privateslot

Definition at line 615 of file handeye_control_widget.cpp.

◆ computeExecution()

void moveit_rviz_plugin::ControlTabWidget::computeExecution ( )

Definition at line 1045 of file handeye_control_widget.cpp.

◆ computePlan()

void moveit_rviz_plugin::ControlTabWidget::computePlan ( )

Definition at line 972 of file handeye_control_widget.cpp.

◆ createSolverInstance()

bool moveit_rviz_plugin::ControlTabWidget::createSolverInstance ( const std::string &  plugin_name)

Definition at line 338 of file handeye_control_widget.cpp.

◆ executeFinished

void moveit_rviz_plugin::ControlTabWidget::executeFinished ( )
privateslot

Definition at line 1093 of file handeye_control_widget.cpp.

◆ fillPlanningGroupNameComboBox()

void moveit_rviz_plugin::ControlTabWidget::fillPlanningGroupNameComboBox ( )

Definition at line 712 of file handeye_control_widget.cpp.

◆ fillSolverTypes()

void moveit_rviz_plugin::ControlTabWidget::fillSolverTypes ( const std::vector< std::string > &  plugins)

Definition at line 355 of file handeye_control_widget.cpp.

◆ frameNamesEmpty()

bool moveit_rviz_plugin::ControlTabWidget::frameNamesEmpty ( )

Definition at line 500 of file handeye_control_widget.cpp.

◆ loadJointStateBtnClicked

void moveit_rviz_plugin::ControlTabWidget::loadJointStateBtnClicked ( bool  clicked)
privateslot

Definition at line 892 of file handeye_control_widget.cpp.

◆ loadSamplesBtnClicked

void moveit_rviz_plugin::ControlTabWidget::loadSamplesBtnClicked ( bool  clicked)
privateslot

Definition at line 791 of file handeye_control_widget.cpp.

◆ loadSolverPlugin()

bool moveit_rviz_plugin::ControlTabWidget::loadSolverPlugin ( std::vector< std::string > &  plugins)

Definition at line 315 of file handeye_control_widget.cpp.

◆ loadWidget()

void moveit_rviz_plugin::ControlTabWidget::loadWidget ( const rviz::Config config)

Definition at line 279 of file handeye_control_widget.cpp.

◆ parseSolverName()

std::string moveit_rviz_plugin::ControlTabWidget::parseSolverName ( const std::string &  solver_name,
char  delimiter 
)

Definition at line 369 of file handeye_control_widget.cpp.

◆ planFinished

void moveit_rviz_plugin::ControlTabWidget::planFinished ( )
privateslot

Definition at line 1060 of file handeye_control_widget.cpp.

◆ planningGroupNameChanged

void moveit_rviz_plugin::ControlTabWidget::planningGroupNameChanged ( const QString &  text)
privateslot

Definition at line 679 of file handeye_control_widget.cpp.

◆ planningGroupNamespaceChanged

void moveit_rviz_plugin::ControlTabWidget::planningGroupNamespaceChanged ( )
privateslot

◆ saveCameraPoseBtnClicked

void moveit_rviz_plugin::ControlTabWidget::saveCameraPoseBtnClicked ( bool  clicked)
privateslot

Definition at line 628 of file handeye_control_widget.cpp.

◆ saveJointStateBtnClicked

void moveit_rviz_plugin::ControlTabWidget::saveJointStateBtnClicked ( bool  clicked)
privateslot

Definition at line 737 of file handeye_control_widget.cpp.

◆ saveSamplesBtnClicked

void moveit_rviz_plugin::ControlTabWidget::saveSamplesBtnClicked ( bool  clicked)
privateslot

Definition at line 833 of file handeye_control_widget.cpp.

◆ saveWidget()

void moveit_rviz_plugin::ControlTabWidget::saveWidget ( rviz::Config config)

Definition at line 309 of file handeye_control_widget.cpp.

◆ sensorPoseUpdate

void moveit_rviz_plugin::ControlTabWidget::sensorPoseUpdate ( double  x,
double  y,
double  z,
double  rx,
double  ry,
double  rz 
)
signal

◆ setGroupName

void moveit_rviz_plugin::ControlTabWidget::setGroupName ( const std::string &  group_name)
privateslot

Definition at line 691 of file handeye_control_widget.cpp.

◆ setTFTool()

void moveit_rviz_plugin::ControlTabWidget::setTFTool ( rviz_visual_tools::TFVisualToolsPtr tf_pub)

Definition at line 524 of file handeye_control_widget.cpp.

◆ solveBtnClicked

void moveit_rviz_plugin::ControlTabWidget::solveBtnClicked ( bool  clicked)
privateslot

Definition at line 419 of file handeye_control_widget.cpp.

◆ solveCameraRobotPose()

bool moveit_rviz_plugin::ControlTabWidget::solveCameraRobotPose ( )

Definition at line 424 of file handeye_control_widget.cpp.

◆ takeSampleBtnClicked

void moveit_rviz_plugin::ControlTabWidget::takeSampleBtnClicked ( bool  clicked)
privateslot

Definition at line 578 of file handeye_control_widget.cpp.

◆ takeTransformSamples()

bool moveit_rviz_plugin::ControlTabWidget::takeTransformSamples ( )

Definition at line 381 of file handeye_control_widget.cpp.

◆ updateFrameNames

void moveit_rviz_plugin::ControlTabWidget::updateFrameNames ( std::map< std::string, std::string >  names)
slot

Definition at line 570 of file handeye_control_widget.cpp.

◆ UpdateSensorMountType

void moveit_rviz_plugin::ControlTabWidget::UpdateSensorMountType ( int  index)
slot

Definition at line 550 of file handeye_control_widget.cpp.

Member Data Documentation

◆ auto_execute_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::auto_execute_btn_
private

Definition at line 262 of file handeye_control_widget.h.

◆ auto_plan_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::auto_plan_btn_
private

Definition at line 261 of file handeye_control_widget.h.

◆ auto_progress_

ProgressBarWidget* moveit_rviz_plugin::ControlTabWidget::auto_progress_
private

Definition at line 266 of file handeye_control_widget.h.

◆ auto_skip_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::auto_skip_btn_
private

Definition at line 263 of file handeye_control_widget.h.

◆ auto_started_

bool moveit_rviz_plugin::ControlTabWidget::auto_started_
private

Definition at line 284 of file handeye_control_widget.h.

◆ calibration_display_

HandEyeCalibrationDisplay* moveit_rviz_plugin::ControlTabWidget::calibration_display_
private

Definition at line 235 of file handeye_control_widget.h.

◆ calibration_solver_

QComboBox* moveit_rviz_plugin::ControlTabWidget::calibration_solver_
private

Definition at line 245 of file handeye_control_widget.h.

◆ camera_robot_pose_

Eigen::Isometry3d moveit_rviz_plugin::ControlTabWidget::camera_robot_pose_
private

Definition at line 281 of file handeye_control_widget.h.

◆ current_plan_

moveit::planning_interface::MoveGroupInterface::PlanPtr moveit_rviz_plugin::ControlTabWidget::current_plan_
private

Definition at line 301 of file handeye_control_widget.h.

◆ effector_wrt_world_

std::vector<Eigen::Isometry3d> moveit_rviz_plugin::ControlTabWidget::effector_wrt_world_
private

Definition at line 278 of file handeye_control_widget.h.

◆ execution_watcher_

QFutureWatcher<void>* moveit_rviz_plugin::ControlTabWidget::execution_watcher_
private

Definition at line 269 of file handeye_control_widget.h.

◆ frame_names_

std::map<std::string, std::string> moveit_rviz_plugin::ControlTabWidget::frame_names_
private

Definition at line 276 of file handeye_control_widget.h.

◆ from_frame_tag_

std::string moveit_rviz_plugin::ControlTabWidget::from_frame_tag_
private

Definition at line 280 of file handeye_control_widget.h.

◆ group_name_

QComboBox* moveit_rviz_plugin::ControlTabWidget::group_name_
private

Definition at line 260 of file handeye_control_widget.h.

◆ joint_names_

std::vector<std::string> moveit_rviz_plugin::ControlTabWidget::joint_names_
private

Definition at line 283 of file handeye_control_widget.h.

◆ joint_states_

std::vector<std::vector<double> > moveit_rviz_plugin::ControlTabWidget::joint_states_
private

Definition at line 282 of file handeye_control_widget.h.

◆ load_joint_state_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::load_joint_state_btn_
private

Definition at line 249 of file handeye_control_widget.h.

◆ load_samples_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::load_samples_btn_
private

Definition at line 251 of file handeye_control_widget.h.

◆ move_group_

moveit::planning_interface::MoveGroupInterfacePtr moveit_rviz_plugin::ControlTabWidget::move_group_
private

Definition at line 300 of file handeye_control_widget.h.

◆ nh_

ros::NodeHandle moveit_rviz_plugin::ControlTabWidget::nh_
private

Definition at line 291 of file handeye_control_widget.h.

◆ object_wrt_sensor_

std::vector<Eigen::Isometry3d> moveit_rviz_plugin::ControlTabWidget::object_wrt_sensor_
private

Definition at line 279 of file handeye_control_widget.h.

◆ plan_watcher_

QFutureWatcher<void>* moveit_rviz_plugin::ControlTabWidget::plan_watcher_
private

Definition at line 268 of file handeye_control_widget.h.

◆ planning_res_

PLANNING_RESULT moveit_rviz_plugin::ControlTabWidget::planning_res_
private

Definition at line 285 of file handeye_control_widget.h.

◆ planning_scene_monitor_

planning_scene_monitor::PlanningSceneMonitorPtr moveit_rviz_plugin::ControlTabWidget::planning_scene_monitor_
private

Definition at line 299 of file handeye_control_widget.h.

◆ reprojection_error_label_

QLabel* moveit_rviz_plugin::ControlTabWidget::reprojection_error_label_
private

Definition at line 242 of file handeye_control_widget.h.

◆ reset_sample_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::reset_sample_btn_
private

Definition at line 256 of file handeye_control_widget.h.

◆ sample_tree_view_

QTreeView* moveit_rviz_plugin::ControlTabWidget::sample_tree_view_
private

Definition at line 241 of file handeye_control_widget.h.

◆ save_camera_pose_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::save_camera_pose_btn_
private

Definition at line 250 of file handeye_control_widget.h.

◆ save_joint_state_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::save_joint_state_btn_
private

Definition at line 248 of file handeye_control_widget.h.

◆ save_samples_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::save_samples_btn_
private

Definition at line 252 of file handeye_control_widget.h.

◆ sensor_mount_type_

mhc::SensorMountType moveit_rviz_plugin::ControlTabWidget::sensor_mount_type_
private

Definition at line 275 of file handeye_control_widget.h.

◆ solve_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::solve_btn_
private

Definition at line 257 of file handeye_control_widget.h.

◆ solver_

pluginlib::UniquePtr<moveit_handeye_calibration::HandEyeSolverBase> moveit_rviz_plugin::ControlTabWidget::solver_
private

Definition at line 298 of file handeye_control_widget.h.

◆ solver_plugins_loader_

std::unique_ptr<pluginlib::ClassLoader<moveit_handeye_calibration::HandEyeSolverBase> > moveit_rviz_plugin::ControlTabWidget::solver_plugins_loader_
private

Definition at line 297 of file handeye_control_widget.h.

◆ take_sample_btn_

QPushButton* moveit_rviz_plugin::ControlTabWidget::take_sample_btn_
private

Definition at line 255 of file handeye_control_widget.h.

◆ tf_buffer_

std::shared_ptr<tf2_ros::Buffer> moveit_rviz_plugin::ControlTabWidget::tf_buffer_
private

Definition at line 294 of file handeye_control_widget.h.

◆ tf_listener_

tf2_ros::TransformListener moveit_rviz_plugin::ControlTabWidget::tf_listener_
private

Definition at line 295 of file handeye_control_widget.h.

◆ tf_tools_

rviz_visual_tools::TFVisualToolsPtr moveit_rviz_plugin::ControlTabWidget::tf_tools_
private

Definition at line 296 of file handeye_control_widget.h.

◆ tree_view_model_

QStandardItemModel* moveit_rviz_plugin::ControlTabWidget::tree_view_model_
private

Definition at line 243 of file handeye_control_widget.h.


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


moveit_calibration_gui
Author(s): Yu Yan
autogenerated on Fri Oct 18 2024 02:14:15