Public Member Functions | Private Member Functions | Private Attributes
srs_interaction_primitives::Object Class Reference

#include <object.h>

Inheritance diagram for srs_interaction_primitives::Object:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void addPreGraspPosition (int pos_id, geometry_msgs::Pose pose)
 Sets specified pre-grasp position.
void addPregraspPositions ()
 Adds grasping positions.
geometry_msgs::Point getBoundingBoxLWH ()
std::string getResource ()
 Gets the resource file with primitive's model (and material).
arm_navigation_msgs::Shape getShape ()
 Gets shape of the mesh.
bool getUseMaterial ()
 Gets usage of defined material or color.
void insert ()
void menuCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Object (InteractiveMarkerServerPtr server, std::string frame_id, std::string name)
void objectCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void removePreGraspPosition (int pos_id)
 Removes specified pre-grasp position.
void removePregraspPositions ()
 Removes grasping positions.
virtual void setAllowObjectInteraction (bool allow)
 Allows or denies interaction with Object.
void setAllowPregrasp (bool allow_pregrasp)
void setBoundingBoxLWH (geometry_msgs::Point bounding_box_lwh)
void setPoseLWH (geometry_msgs::Pose pose, geometry_msgs::Point bounding_box_lwh)
void setResource (std::string resource)
 Sets resource file with primitive's model (and material).
void setShape (arm_navigation_msgs::Shape shape)
 Sets shape of the mesh.
void setUseMaterial (bool use_material)
 Sets usage of defined material or color.
void updateControls ()
 Updates visible controls.

Private Member Functions

void create ()
 Create Object.
void createBoundingBoxControl ()
void createMenu ()
 Create menu.
void createMesh ()

Private Attributes

bool allow_object_interaction_
bool allow_pregrasp_
geometry_msgs::Point bounding_box_lwh_
interactive_markers::MenuHandler::EntryHandle menu_handler_interaction_
interactive_markers::MenuHandler::EntryHandle menu_handler_interaction_movement_
interactive_markers::MenuHandler::EntryHandle menu_handler_interaction_rotation_
interactive_markers::MenuHandler::EntryHandle menu_handler_move_to_pregrasp_
interactive_markers::MenuHandler::EntryHandle menu_handler_show_pregrasp_
visualization_msgs::Marker mesh_
bool move_arm_to_pregrasp_onclick_
ObjectResource object_resource_
PreGraspPosition pregrasp1_
visualization_msgs::InteractiveMarkerControl pregrasp1Control_
PreGraspPosition pregrasp2_
visualization_msgs::InteractiveMarkerControl pregrasp2Control_
PreGraspPosition pregrasp3_
visualization_msgs::InteractiveMarkerControl pregrasp3Control_
PreGraspPosition pregrasp4_
visualization_msgs::InteractiveMarkerControl pregrasp4Control_
PreGraspPosition pregrasp5_
visualization_msgs::InteractiveMarkerControl pregrasp5Control_
PreGraspPosition pregrasp6_
visualization_msgs::InteractiveMarkerControl pregrasp6Control_
std::string resource_
arm_navigation_msgs::Shape shape_
bool show_pregrasp_control_
bool translated_
bool use_material_

Detailed Description

This class represents detected object and it's bounding box.

Object with Bounding Box is designed to be the direct output of the detectors. It shows object's mesh together with it's Bounding Box. It can also show pre-grasp positions and can be translated, rotated or scaled.

Author:
Tomas Lokaj
See also:
http://ros.org/wiki/srs_env_model#Object

Definition at line 78 of file object.h.


Constructor & Destructor Documentation

srs_interaction_primitives::Object::Object ( InteractiveMarkerServerPtr  server,
std::string  frame_id,
std::string  name 
)

Constructor.

Parameters:
serveris Interactive marker server
frame_idis fixed frame
nameis name of this object

Member Function Documentation

Sets specified pre-grasp position.

Parameters:
pos_numis specified position number (1-6)
poseis pre-grasp position and orientation

Definition at line 491 of file object.cpp.

Adds grasping positions.

Definition at line 324 of file object.cpp.

void srs_interaction_primitives::Object::create ( ) [private, virtual]

Create Object.

Reimplemented from srs_interaction_primitives::BoundingBox.

Definition at line 597 of file object.cpp.

Create menu.

Reimplemented from srs_interaction_primitives::BoundingBox.

Definition at line 259 of file object.cpp.

Definition at line 566 of file object.cpp.

Gets object's bounding box

Returns:
bounding_box_lwh is bounding box length, width and height

Definition at line 107 of file object.h.

Gets the resource file with primitive's model (and material).

Returns:
resource path to the resource file

Definition at line 142 of file object.h.

Gets shape of the mesh.

Returns:
shape of t he mesh

Definition at line 179 of file object.h.

Gets usage of defined material or color.

Returns:
use_material material (true), color (false)

Definition at line 160 of file object.h.

Creates and inserts object into Interactive Marker Server

Reimplemented from srs_interaction_primitives::BoundingBox.

Definition at line 627 of file object.cpp.

void srs_interaction_primitives::Object::menuCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Menu callback

Reimplemented from srs_interaction_primitives::BoundingBox.

Definition at line 107 of file object.cpp.

void srs_interaction_primitives::Object::objectCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Callback

Definition at line 86 of file object.cpp.

Removes specified pre-grasp position.

Parameters:
pos_numis specified position number (1-6)

Definition at line 536 of file object.cpp.

Removes grasping positions.

Definition at line 480 of file object.cpp.

Allows or denies interaction with Object.

Parameters:
allowis true or false

Definition at line 63 of file object.cpp.

Allows or disables showing of preg-rasp menu entries

Parameters:
allow_pregraspTrue to show pre-grasp menu entries, False otherwise

Definition at line 123 of file object.h.

Sets object's bounding box

Parameters:
bounding_box_lwhis bounding box length, width and height

Definition at line 98 of file object.h.

Sets position orientation of the object and dimension of the bounding box.

Parameters:
poseis object's position and orientation
bounding_box_lwhis length, width and height of the bounding box

Definition at line 587 of file object.cpp.

void srs_interaction_primitives::Object::setResource ( std::string  resource) [inline]

Sets resource file with primitive's model (and material).

Parameters:
resourcepath to the resource file

Definition at line 132 of file object.h.

Sets shape of the mesh.

Parameters:
shapeis shape

Definition at line 169 of file object.h.

Sets usage of defined material or color.

Parameters:
use_materialmaterial (true), color (false)

Definition at line 151 of file object.h.

Updates visible controls.

Reimplemented from srs_interaction_primitives::Primitive.

Definition at line 526 of file object.cpp.


Member Data Documentation

Definition at line 241 of file object.h.

Definition at line 241 of file object.h.

Definition at line 243 of file object.h.

Definition at line 254 of file object.h.

Definition at line 254 of file object.h.

Definition at line 254 of file object.h.

Definition at line 254 of file object.h.

Definition at line 254 of file object.h.

visualization_msgs::Marker srs_interaction_primitives::Object::mesh_ [private]

Definition at line 236 of file object.h.

Definition at line 240 of file object.h.

Definition at line 235 of file object.h.

Definition at line 248 of file object.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Object::pregrasp1Control_ [private]

Definition at line 250 of file object.h.

Definition at line 248 of file object.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Object::pregrasp2Control_ [private]

Definition at line 250 of file object.h.

Definition at line 248 of file object.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Object::pregrasp3Control_ [private]

Definition at line 250 of file object.h.

Definition at line 248 of file object.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Object::pregrasp4Control_ [private]

Definition at line 250 of file object.h.

Definition at line 248 of file object.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Object::pregrasp5Control_ [private]

Definition at line 250 of file object.h.

Definition at line 248 of file object.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Object::pregrasp6Control_ [private]

Definition at line 250 of file object.h.

Definition at line 238 of file object.h.

Definition at line 237 of file object.h.

Definition at line 246 of file object.h.

Definition at line 244 of file object.h.

Definition at line 239 of file object.h.


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


srs_interaction_primitives
Author(s): Tomas Lokaj, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Mon Oct 6 2014 07:55:11