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_;
120 void makeBoxControls(visualization_msgs::InteractiveMarker& interactive_marker,
bool is_center);
127 void makeSphereControls(visualization_msgs::InteractiveMarker& interactive_marker,
bool is_center);
143 #endif // INTERACTIVE_ROI_SELECTION_H
tf::Quaternion center_orientation_
bool getInteractiveRoi(rc_pick_client::RegionOfInterest &roi)
Provides the region of interest from the server.
void makeSphereControls(visualization_msgs::InteractiveMarker &interactive_marker, bool is_center)
Generate controls of a sphere interactive marker.
void updateCenterMarker()
Update the center interactive marker in rviz.
void processSphereSizeFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Process changes on the region of interest's size.
tf::Vector3 center_position_
InteractiveRoiSelection()
Constructor.
void computeVectorRotation(const tf::Vector3 &v, const tf::Quaternion &q, tf::Vector3 &rot_v)
Compute the rotation of a vector by a quaternion.
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server_
void processRoiPoseFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Process changes on the position and rotation of the region of interest.
bool setInteractiveRoi(const rc_pick_client::RegionOfInterest &roi)
Sets a new region of interest in the server.
void makeBoxControls(visualization_msgs::InteractiveMarker &interactive_marker, bool is_center)
Generate controls of a box interactive marker.
std::shared_ptr< ros::NodeHandle > nh_
visualization_msgs::Marker makeMarker(tf::Vector3 box_dimensions, bool is_center)
Generate a marker.
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.
rc_pick_client::RegionOfInterest interactive_roi_
virtual ~InteractiveRoiSelection()
void processRoiSizeFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Process changes on the region of interest's size.