rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
rapid::DragBoxMarker Class Reference

An interactive marker for a box with draggable sides. More...

#include <drag_box_marker.h>

Public Member Functions

 DragBoxMarker (const std::string &name, interactive_markers::InteractiveMarkerServer *im_server)
 Constructor. More...
 
void Show ()
 Show the marker. More...
 
void Hide ()
 Erases the marker. More...
 
void set_pose_stamped (const geometry_msgs::PoseStamped &pose_stamped)
 Sets the marker's pose. More...
 
void set_min_x (double min_x)
 Sets the minimum x value of the box. More...
 
void set_max_x (double max_x)
 Sets the maximum x value of the box. More...
 
void set_min_y (double min_y)
 Sets the minimum y value of the box. More...
 
void set_max_y (double max_y)
 Sets the maximum y value of the box. More...
 
void set_min_z (double min_z)
 Sets the minimum z value of the box. More...
 
void set_max_z (double max_z)
 Sets the maximum z value of the box. More...
 
geometry_msgs::PoseStamped pose_stamped ()
 
double min_x ()
 
double max_x ()
 
double min_y ()
 
double max_y ()
 
double min_z ()
 
double max_z ()
 

Detailed Description

An interactive marker for a box with draggable sides.

The box has a fixed pose but adjustable-length sides. After the user adjusts the side lengths, you can access the sides via min_x, max_x, etc. Note that the pose is not necessarily centered on or contained in the box. For example, if the pose could be at the origin while min_x=0.05 and max_x = 0.15. The box would appear to be centered at x=0.1.

Usage:

DragBoxMarker box("left_hand", &im_server);
box.set_pose_stamped(ps);
box.set_min_x(-0.15);
box.set_max_x(0.15);
box.set_min_y(-0.15);
box.set_max_y(0.15);
box.set_min_z(-0.15);
box.set_max_z(0.15);
box.Show();
// Wait for user input, e.g., std::cin or waitKey
double min_x = box.min_x();
box.Hide();

Definition at line 38 of file drag_box_marker.h.

Constructor & Destructor Documentation

rapid::DragBoxMarker::DragBoxMarker ( const std::string &  name,
interactive_markers::InteractiveMarkerServer *  im_server 
)

Constructor.

Parameters
[in]nameThe name of the this interactive marker.
[in,out]im_serverThe interactive marker server to add this marker to.

Member Function Documentation

void rapid::DragBoxMarker::Hide ( )

Erases the marker.

double rapid::DragBoxMarker::max_x ( )
Returns
The maximum x value of the box.
double rapid::DragBoxMarker::max_y ( )
Returns
The maximum y value of the box.
double rapid::DragBoxMarker::max_z ( )
Returns
The maximum z value of the box.
double rapid::DragBoxMarker::min_x ( )
Returns
The minimum x value of the box.
double rapid::DragBoxMarker::min_y ( )
Returns
The minimum y value of the box.
double rapid::DragBoxMarker::min_z ( )
Returns
The minimum z value of the box.
geometry_msgs::PoseStamped rapid::DragBoxMarker::pose_stamped ( )
Returns
The pose of the box.
void rapid::DragBoxMarker::set_max_x ( double  max_x)

Sets the maximum x value of the box.

Parameters
[in]max_xThe maximum x value of the box.
void rapid::DragBoxMarker::set_max_y ( double  max_y)

Sets the maximum y value of the box.

Parameters
[in]max_yThe maximum y value of the box.
void rapid::DragBoxMarker::set_max_z ( double  max_z)

Sets the maximum z value of the box.

Parameters
[in]max_xThe maximum z value of the box.
void rapid::DragBoxMarker::set_min_x ( double  min_x)

Sets the minimum x value of the box.

Parameters
[in]min_xThe minimum x value of the box.
void rapid::DragBoxMarker::set_min_y ( double  min_y)

Sets the minimum y value of the box.

Parameters
[in]min_yThe minimum y value of the box.
void rapid::DragBoxMarker::set_min_z ( double  min_z)

Sets the minimum z value of the box.

Parameters
[in]min_zThe minimum z value of the box.
void rapid::DragBoxMarker::set_pose_stamped ( const geometry_msgs::PoseStamped &  pose_stamped)

Sets the marker's pose.

void rapid::DragBoxMarker::Show ( )

Show the marker.


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