Go to the documentation of this file.
   33 #ifndef INTERACTIVE_ROI_SELECTION_H 
   34 #define INTERACTIVE_ROI_SELECTION_H 
   40 #include <rc_pick_client/RegionOfInterest.h> 
   74   std::shared_ptr<ros::NodeHandle> 
nh_;
 
  113   visualization_msgs::Marker 
makeMarker(tf::Vector3 box_dimensions, 
bool is_center);
 
  120   void makeBoxControls(visualization_msgs::InteractiveMarker& interactive_marker, 
bool is_center);
 
  127   void makeSphereControls(visualization_msgs::InteractiveMarker& interactive_marker, 
bool is_center);
 
  139                              const tf::Vector3& position, 
bool is_center, tf::Vector3 box_dimensions,
 
  143 #endif  // INTERACTIVE_ROI_SELECTION_H 
  
bool setInteractiveRoi(const rc_pick_client::RegionOfInterest &roi)
Sets a new region of interest in the server.
rc_pick_client::RegionOfInterest interactive_roi_
virtual ~InteractiveRoiSelection()
InteractiveRoiSelection()
Constructor.
tf::Quaternion center_orientation_
void updateCenterMarker()
Update the center interactive marker in rviz.
bool getInteractiveRoi(rc_pick_client::RegionOfInterest &roi)
Provides the region of interest from the server.
void processSphereSizeFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Process changes on the region of interest's size.
void processRoiPoseFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Process changes on the position and rotation of the region of interest.
std::shared_ptr< ros::NodeHandle > nh_
void makeSphereControls(visualization_msgs::InteractiveMarker &interactive_marker, bool is_center)
Generate controls of a sphere interactive marker.
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
void makeInteractiveMarker(std::string int_marker_name, std::string int_marker_description, const tf::Vector3 &position, bool is_center, tf::Vector3 box_dimensions, tf::Quaternion box_orientation)
Generate an interactive marker.
void processRoiSizeFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Process changes on the region of interest's size.
tf::Vector3 center_position_
void makeBoxControls(visualization_msgs::InteractiveMarker &interactive_marker, bool is_center)
Generate controls of a box interactive marker.
visualization_msgs::Marker makeMarker(tf::Vector3 box_dimensions, bool is_center)
Generate a marker.
void computeVectorRotation(const tf::Vector3 &v, const tf::Quaternion &q, tf::Vector3 &rot_v)
Compute the rotation of a vector by a quaternion.
rc_roi_manager_gui
Author(s): Carlos Xavier Garcia Briones 
autogenerated on Thu Feb 3 2022 03:29:05