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

#include <handeye_context_widget.h>

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

Public Slots

void setCameraInfo (sensor_msgs::CameraInfo camera_info)
 
void setOpticalFrame (const std::string &frame_id)
 
void updateCameraPose (double tx, double ty, double tz, double rx, double ry, double rz)
 

Signals

void frameNameChanged (std::map< std::string, std::string > names)
 
void sensorMountTypeChanged (int index)
 

Public Member Functions

 ContextTabWidget (HandEyeCalibrationDisplay *pdisplay, QWidget *parent=Q_NULLPTR)
 
visualization_msgs::Marker getCameraFOVMarker (const Eigen::Isometry3d &pose, const shape_msgs::Mesh &mesh, rvt::colors color, double alpha, std::string frame_id)
 
visualization_msgs::Marker getCameraFOVMarker (const geometry_msgs::Pose &pose, const shape_msgs::Mesh &mesh, rvt::colors color, double alpha, std::string frame_id)
 
void loadWidget (const rviz::Config &config)
 
void saveWidget (rviz::Config &config)
 
void setCameraPose (double tx, double ty, double tz, double rx, double ry, double rz)
 
void setTFTool (rviz_visual_tools::TFVisualToolsPtr &tf_pub)
 
void updateAllMarkers ()
 
void updateFOVPose ()
 
 ~ContextTabWidget ()
 

Static Public Member Functions

static shape_msgs::Mesh getCameraFOVMesh (const sensor_msgs::CameraInfo &camera_info, double maxdist)
 

Private Slots

void updateCameraMarkerPose (double value)
 
void updateFrameName (int index)
 
void updateSensorMountType (int index)
 

Private Attributes

HandEyeCalibrationDisplaycalibration_display_
 
sensor_msgs::CameraInfoPtr camera_info_
 
Eigen::Isometry3d camera_pose_
 
Eigen::Isometry3d fov_pose_
 
std::map< std::string, TFFrameNameComboBox * > frames_
 
std::map< std::string, SliderWidget * > guess_pose_
 
std::string optical_frame_
 
QComboBox * sensor_mount_type_
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListener tf_listener_
 
rviz_visual_tools::TFVisualToolsPtr tf_tools_
 
moveit_visual_tools::MoveItVisualToolsPtr visual_tools_
 

Detailed Description

Definition at line 182 of file handeye_context_widget.h.

Constructor & Destructor Documentation

◆ ContextTabWidget()

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

Definition at line 189 of file handeye_context_widget.cpp.

◆ ~ContextTabWidget()

moveit_rviz_plugin::ContextTabWidget::~ContextTabWidget ( )
inline

Definition at line 187 of file handeye_context_widget.h.

Member Function Documentation

◆ frameNameChanged

void moveit_rviz_plugin::ContextTabWidget::frameNameChanged ( std::map< std::string, std::string >  names)
signal

◆ getCameraFOVMarker() [1/2]

visualization_msgs::Marker moveit_rviz_plugin::ContextTabWidget::getCameraFOVMarker ( const Eigen::Isometry3d &  pose,
const shape_msgs::Mesh &  mesh,
rvt::colors  color,
double  alpha,
std::string  frame_id 
)

Definition at line 461 of file handeye_context_widget.cpp.

◆ getCameraFOVMarker() [2/2]

visualization_msgs::Marker moveit_rviz_plugin::ContextTabWidget::getCameraFOVMarker ( const geometry_msgs::Pose pose,
const shape_msgs::Mesh &  mesh,
rvt::colors  color,
double  alpha,
std::string  frame_id 
)

Definition at line 468 of file handeye_context_widget.cpp.

◆ getCameraFOVMesh()

shape_msgs::Mesh moveit_rviz_plugin::ContextTabWidget::getCameraFOVMesh ( const sensor_msgs::CameraInfo &  camera_info,
double  maxdist 
)
static

Definition at line 421 of file handeye_context_widget.cpp.

◆ loadWidget()

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

Definition at line 281 of file handeye_context_widget.cpp.

◆ saveWidget()

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

Definition at line 315 of file handeye_context_widget.cpp.

◆ sensorMountTypeChanged

void moveit_rviz_plugin::ContextTabWidget::sensorMountTypeChanged ( int  index)
signal

◆ setCameraInfo

void moveit_rviz_plugin::ContextTabWidget::setCameraInfo ( sensor_msgs::CameraInfo  camera_info)
slot

Definition at line 500 of file handeye_context_widget.cpp.

◆ setCameraPose()

void moveit_rviz_plugin::ContextTabWidget::setCameraPose ( double  tx,
double  ty,
double  tz,
double  rx,
double  ry,
double  rz 
)

Definition at line 494 of file handeye_context_widget.cpp.

◆ setOpticalFrame

void moveit_rviz_plugin::ContextTabWidget::setOpticalFrame ( const std::string &  frame_id)
slot

Definition at line 513 of file handeye_context_widget.cpp.

◆ setTFTool()

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

Definition at line 326 of file handeye_context_widget.cpp.

◆ updateAllMarkers()

void moveit_rviz_plugin::ContextTabWidget::updateAllMarkers ( )

Definition at line 331 of file handeye_context_widget.cpp.

◆ updateCameraMarkerPose

void moveit_rviz_plugin::ContextTabWidget::updateCameraMarkerPose ( double  value)
privateslot

Definition at line 567 of file handeye_context_widget.cpp.

◆ updateCameraPose

void moveit_rviz_plugin::ContextTabWidget::updateCameraPose ( double  tx,
double  ty,
double  tz,
double  rx,
double  ry,
double  rz 
)
slot

Definition at line 519 of file handeye_context_widget.cpp.

◆ updateFOVPose()

void moveit_rviz_plugin::ContextTabWidget::updateFOVPose ( )

Definition at line 397 of file handeye_context_widget.cpp.

◆ updateFrameName

void moveit_rviz_plugin::ContextTabWidget::updateFrameName ( int  index)
privateslot

Definition at line 541 of file handeye_context_widget.cpp.

◆ updateSensorMountType

void moveit_rviz_plugin::ContextTabWidget::updateSensorMountType ( int  index)
privateslot

Definition at line 531 of file handeye_context_widget.cpp.

Member Data Documentation

◆ calibration_display_

HandEyeCalibrationDisplay* moveit_rviz_plugin::ContextTabWidget::calibration_display_
private

Definition at line 238 of file handeye_context_widget.h.

◆ camera_info_

sensor_msgs::CameraInfoPtr moveit_rviz_plugin::ContextTabWidget::camera_info_
private

Definition at line 257 of file handeye_context_widget.h.

◆ camera_pose_

Eigen::Isometry3d moveit_rviz_plugin::ContextTabWidget::camera_pose_
private

Definition at line 260 of file handeye_context_widget.h.

◆ fov_pose_

Eigen::Isometry3d moveit_rviz_plugin::ContextTabWidget::fov_pose_
private

Definition at line 265 of file handeye_context_widget.h.

◆ frames_

std::map<std::string, TFFrameNameComboBox*> moveit_rviz_plugin::ContextTabWidget::frames_
private

Definition at line 248 of file handeye_context_widget.h.

◆ guess_pose_

std::map<std::string, SliderWidget*> moveit_rviz_plugin::ContextTabWidget::guess_pose_
private

Definition at line 251 of file handeye_context_widget.h.

◆ optical_frame_

std::string moveit_rviz_plugin::ContextTabWidget::optical_frame_
private

Definition at line 262 of file handeye_context_widget.h.

◆ sensor_mount_type_

QComboBox* moveit_rviz_plugin::ContextTabWidget::sensor_mount_type_
private

Definition at line 245 of file handeye_context_widget.h.

◆ tf_buffer_

tf2_ros::Buffer moveit_rviz_plugin::ContextTabWidget::tf_buffer_
private

Definition at line 273 of file handeye_context_widget.h.

◆ tf_listener_

tf2_ros::TransformListener moveit_rviz_plugin::ContextTabWidget::tf_listener_
private

Definition at line 274 of file handeye_context_widget.h.

◆ tf_tools_

rviz_visual_tools::TFVisualToolsPtr moveit_rviz_plugin::ContextTabWidget::tf_tools_
private

Definition at line 272 of file handeye_context_widget.h.

◆ visual_tools_

moveit_visual_tools::MoveItVisualToolsPtr moveit_rviz_plugin::ContextTabWidget::visual_tools_
private

Definition at line 271 of file handeye_context_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