Public Member Functions | Private Member Functions | Private Attributes | List of all members
rc_roi_manager_gui::InteractiveRoiSelection Class Reference

#include <interactive_roi_selection.h>

Public Member Functions

bool getInteractiveRoi (rc_pick_client::RegionOfInterest &roi)
 Provides the region of interest from the server. More...
 
 InteractiveRoiSelection ()
 Constructor. More...
 
bool setInteractiveRoi (const rc_pick_client::RegionOfInterest &roi)
 Sets a new region of interest in the server. More...
 
virtual ~InteractiveRoiSelection ()
 

Private Member Functions

void computeVectorRotation (const tf::Vector3 &v, const tf::Quaternion &q, tf::Vector3 &rot_v)
 Compute the rotation of a vector by a quaternion. More...
 
void makeBoxControls (visualization_msgs::InteractiveMarker &interactive_marker, bool is_center)
 Generate controls of a box interactive marker. More...
 
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. More...
 
visualization_msgs::Marker makeMarker (tf::Vector3 box_dimensions, bool is_center)
 Generate a marker. More...
 
void makeSphereControls (visualization_msgs::InteractiveMarker &interactive_marker, bool is_center)
 Generate controls of a sphere interactive marker. More...
 
void processRoiPoseFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Process changes on the position and rotation of the region of interest. More...
 
void processRoiSizeFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Process changes on the region of interest's size. More...
 
void processSphereSizeFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Process changes on the region of interest's size. More...
 
void updateCenterMarker ()
 Update the center interactive marker in rviz. More...
 

Private Attributes

tf::Quaternion center_orientation_
 
tf::Vector3 center_position_
 
tf::Vector3 dimensions_
 
rc_pick_client::RegionOfInterest interactive_roi_
 
std::shared_ptr< ros::NodeHandlenh_
 
boost::shared_ptr< interactive_markers::InteractiveMarkerServerserver_
 

Detailed Description

Definition at line 44 of file interactive_roi_selection.h.

Constructor & Destructor Documentation

rc_roi_manager_gui::InteractiveRoiSelection::InteractiveRoiSelection ( )

Constructor.

Definition at line 39 of file interactive_roi_selection.cc.

rc_roi_manager_gui::InteractiveRoiSelection::~InteractiveRoiSelection ( )
virtual

Definition at line 46 of file interactive_roi_selection.cc.

Member Function Documentation

void rc_roi_manager_gui::InteractiveRoiSelection::computeVectorRotation ( const tf::Vector3 v,
const tf::Quaternion q,
tf::Vector3 rot_v 
)
private

Compute the rotation of a vector by a quaternion.

Parameters
vVector to be rotated
qQuaternion that provides the wanted rotation
rot_vRotated vector

Definition at line 52 of file interactive_roi_selection.cc.

bool rc_roi_manager_gui::InteractiveRoiSelection::getInteractiveRoi ( rc_pick_client::RegionOfInterest &  roi)

Provides the region of interest from the server.

Parameters
roiRegion of interest
Returns

Definition at line 384 of file interactive_roi_selection.cc.

void rc_roi_manager_gui::InteractiveRoiSelection::makeBoxControls ( visualization_msgs::InteractiveMarker &  interactive_marker,
bool  is_center 
)
private

Generate controls of a box interactive marker.

Parameters
interactive_markerInteractive marker
is_centerSet if the marker to create is the center of the region of interest

Definition at line 241 of file interactive_roi_selection.cc.

void rc_roi_manager_gui::InteractiveRoiSelection::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 
)
private

Generate an interactive marker.

Parameters
int_marker_nameInteractive marker's name
int_marker_descriptionInteractive marker's description
positionPosition of the interactive marker
is_centerSet if the marker to create is the center of the region of interest
box_dimensionsDimensions of the interactive marker
box_orientationOrientation of the interactive marker

Definition at line 292 of file interactive_roi_selection.cc.

visualization_msgs::Marker rc_roi_manager_gui::InteractiveRoiSelection::makeMarker ( tf::Vector3  box_dimensions,
bool  is_center 
)
private

Generate a marker.

Parameters
box_dimensionsDimensions of the marker
is_centerSet if the marker to create is the center of the region of interest
Returns
Generated marker

Definition at line 162 of file interactive_roi_selection.cc.

void rc_roi_manager_gui::InteractiveRoiSelection::makeSphereControls ( visualization_msgs::InteractiveMarker &  interactive_marker,
bool  is_center 
)
private

Generate controls of a sphere interactive marker.

Parameters
interactive_markerInteractive marker
is_centerSet if the marker to create is the center of the region of interest

Definition at line 193 of file interactive_roi_selection.cc.

void rc_roi_manager_gui::InteractiveRoiSelection::processRoiPoseFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
private

Process changes on the position and rotation of the region of interest.

Parameters
feedbackcenter marker with updates done in rviz

Definition at line 59 of file interactive_roi_selection.cc.

void rc_roi_manager_gui::InteractiveRoiSelection::processRoiSizeFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
private

Process changes on the region of interest's size.

Parameters
feedbackcorner marker with updates done in rviz

Definition at line 145 of file interactive_roi_selection.cc.

void rc_roi_manager_gui::InteractiveRoiSelection::processSphereSizeFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)
private

Process changes on the region of interest's size.

Parameters
feedbackcorner marker with updates done in rviz

Definition at line 128 of file interactive_roi_selection.cc.

bool rc_roi_manager_gui::InteractiveRoiSelection::setInteractiveRoi ( const rc_pick_client::RegionOfInterest &  roi)

Sets a new region of interest in the server.

Parameters
roiRegion of interest
Returns

Definition at line 345 of file interactive_roi_selection.cc.

void rc_roi_manager_gui::InteractiveRoiSelection::updateCenterMarker ( )
private

Update the center interactive marker in rviz.

Definition at line 138 of file interactive_roi_selection.cc.

Member Data Documentation

tf::Quaternion rc_roi_manager_gui::InteractiveRoiSelection::center_orientation_
private

Definition at line 71 of file interactive_roi_selection.h.

tf::Vector3 rc_roi_manager_gui::InteractiveRoiSelection::center_position_
private

Definition at line 70 of file interactive_roi_selection.h.

tf::Vector3 rc_roi_manager_gui::InteractiveRoiSelection::dimensions_
private

Definition at line 72 of file interactive_roi_selection.h.

rc_pick_client::RegionOfInterest rc_roi_manager_gui::InteractiveRoiSelection::interactive_roi_
private

Definition at line 73 of file interactive_roi_selection.h.

std::shared_ptr<ros::NodeHandle> rc_roi_manager_gui::InteractiveRoiSelection::nh_
private

Definition at line 74 of file interactive_roi_selection.h.

boost::shared_ptr<interactive_markers::InteractiveMarkerServer> rc_roi_manager_gui::InteractiveRoiSelection::server_
private

Definition at line 69 of file interactive_roi_selection.h.


The documentation for this class was generated from the following files:


rc_roi_manager_gui
Author(s): Carlos Xavier Garcia Briones
autogenerated on Sat Feb 13 2021 03:42:01