42 #include <Eigen/Geometry>
52 "The name of the ROS namespace in "
53 "which the move_group node is running",
54 this, SLOT(fillPlanningGroupNameComboBox()),
this);
55 planning_scene_topic_property_ =
57 ros::message_traits::datatype<moveit_msgs::PlanningScene>(),
58 "The topic on which the moveit_msgs::PlanningScene messages are received",
this,
59 SLOT(fillPlanningGroupNameComboBox()),
this);
62 "Camera FOV Marker",
true,
"Enable marker showing camera field of view",
this, SLOT(updateMarkers()),
this);
63 fov_marker_alpha_property_ =
64 new rviz::FloatProperty(
"Marker Alpha", 0.3f,
"Specifies the alpha (transparency) for the rendered marker",
65 fov_marker_enabled_property_, SLOT(updateMarkers()),
this);
66 fov_marker_size_property_ =
67 new rviz::FloatProperty(
"Marker Size", 1.5f,
"Specifies the size (depth in meters) for the rendered marker",
68 fov_marker_enabled_property_, SLOT(updateMarkers()),
this);
71 HandEyeCalibrationDisplay::~HandEyeCalibrationDisplay()
77 void HandEyeCalibrationDisplay::onInitialize()
79 Display::onInitialize();
86 frame_dock_ = window_context->
addPane(
"HandEye Calibration", frame_);
90 void HandEyeCalibrationDisplay::save(
rviz::Config config)
const
92 Display::save(config);
95 frame_->saveWidget(config);
100 void HandEyeCalibrationDisplay::load(
const rviz::Config& config)
102 Display::load(config);
105 frame_->loadWidget(
config);
109 void HandEyeCalibrationDisplay::fillPlanningGroupNameComboBox()
111 if (frame_ && frame_->tab_control_)
113 frame_->tab_control_->fillPlanningGroupNameComboBox();
117 void HandEyeCalibrationDisplay::updateMarkers()
119 if (frame_ && frame_->tab_context_)
121 frame_->tab_context_->updateAllMarkers();