#include <handeye_context_widget.h>
|
| | 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 shape_msgs::Mesh | getCameraFOVMesh (const sensor_msgs::CameraInfo &camera_info, double maxdist) |
| |
Definition at line 182 of file handeye_context_widget.h.
◆ ContextTabWidget()
| moveit_rviz_plugin::ContextTabWidget::ContextTabWidget |
( |
HandEyeCalibrationDisplay * |
pdisplay, |
|
|
QWidget * |
parent = Q_NULLPTR |
|
) |
| |
|
explicit |
◆ ~ContextTabWidget()
| moveit_rviz_plugin::ContextTabWidget::~ContextTabWidget |
( |
| ) |
|
|
inline |
◆ 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 |
|
) |
| |
◆ 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 |
|
) |
| |
◆ getCameraFOVMesh()
| shape_msgs::Mesh moveit_rviz_plugin::ContextTabWidget::getCameraFOVMesh |
( |
const sensor_msgs::CameraInfo & |
camera_info, |
|
|
double |
maxdist |
|
) |
| |
|
static |
◆ loadWidget()
| void moveit_rviz_plugin::ContextTabWidget::loadWidget |
( |
const rviz::Config & |
config | ) |
|
◆ saveWidget()
| void moveit_rviz_plugin::ContextTabWidget::saveWidget |
( |
rviz::Config & |
config | ) |
|
◆ sensorMountTypeChanged
| void moveit_rviz_plugin::ContextTabWidget::sensorMountTypeChanged |
( |
int |
index | ) |
|
|
signal |
◆ setCameraInfo
| void moveit_rviz_plugin::ContextTabWidget::setCameraInfo |
( |
sensor_msgs::CameraInfo |
camera_info | ) |
|
|
slot |
◆ setCameraPose()
| void moveit_rviz_plugin::ContextTabWidget::setCameraPose |
( |
double |
tx, |
|
|
double |
ty, |
|
|
double |
tz, |
|
|
double |
rx, |
|
|
double |
ry, |
|
|
double |
rz |
|
) |
| |
◆ setOpticalFrame
| void moveit_rviz_plugin::ContextTabWidget::setOpticalFrame |
( |
const std::string & |
frame_id | ) |
|
|
slot |
◆ setTFTool()
◆ updateAllMarkers()
| void moveit_rviz_plugin::ContextTabWidget::updateAllMarkers |
( |
| ) |
|
◆ updateCameraMarkerPose
| void moveit_rviz_plugin::ContextTabWidget::updateCameraMarkerPose |
( |
double |
value | ) |
|
|
privateslot |
◆ updateCameraPose
| void moveit_rviz_plugin::ContextTabWidget::updateCameraPose |
( |
double |
tx, |
|
|
double |
ty, |
|
|
double |
tz, |
|
|
double |
rx, |
|
|
double |
ry, |
|
|
double |
rz |
|
) |
| |
|
slot |
◆ updateFOVPose()
| void moveit_rviz_plugin::ContextTabWidget::updateFOVPose |
( |
| ) |
|
◆ updateFrameName
| void moveit_rviz_plugin::ContextTabWidget::updateFrameName |
( |
int |
index | ) |
|
|
privateslot |
◆ updateSensorMountType
| void moveit_rviz_plugin::ContextTabWidget::updateSensorMountType |
( |
int |
index | ) |
|
|
privateslot |
◆ calibration_display_
◆ camera_info_
| sensor_msgs::CameraInfoPtr moveit_rviz_plugin::ContextTabWidget::camera_info_ |
|
private |
◆ camera_pose_
| Eigen::Isometry3d moveit_rviz_plugin::ContextTabWidget::camera_pose_ |
|
private |
◆ fov_pose_
| Eigen::Isometry3d moveit_rviz_plugin::ContextTabWidget::fov_pose_ |
|
private |
◆ frames_
◆ guess_pose_
| std::map<std::string, SliderWidget*> moveit_rviz_plugin::ContextTabWidget::guess_pose_ |
|
private |
◆ optical_frame_
| std::string moveit_rviz_plugin::ContextTabWidget::optical_frame_ |
|
private |
◆ sensor_mount_type_
| QComboBox* moveit_rviz_plugin::ContextTabWidget::sensor_mount_type_ |
|
private |
◆ tf_buffer_
◆ tf_listener_
◆ tf_tools_
◆ visual_tools_
The documentation for this class was generated from the following files: