$search

ShapeMarker Class Reference

#include <shape_marker.h>

List of all members.

Public Member Functions

void createInteractiveMarker ()
 Publish interactive markers for a shape message using interactive marker server.
void createMarker (visualization_msgs::InteractiveMarkerControl &im_ctrl)
 Create marker for the shape and add it to the interactive marker control.
void createShapeMenu ()
 Create menu entries for each shape.
void deleteMarker (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 feedback callback for Delete Marker menu entry
void displayArrows ()
 Display arrows for interactive marker movement.
void displayCentroid ()
 Display the centroid of a shape.
void displayCentroidCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Feedback callback for Display Centroid menu entry.
void displayContour ()
 Display contour of a shape.
void displayContourCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Feedback callback for Display Contour menu entry.
void displayNormal ()
 Display the normal vector of a shape.
void displayNormalCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Feedback callback for normal menu entry.
void displayOrigin ()
 Display the origin of a cylinder.
void displayOriginCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Feedback callback for origin menu entry.
void displaySymAxis ()
 Display the Symmetry axis of a cylinder.
void displaySymAxisCB (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Feedback callback for symmetry axis menu entry with cylinders.
void enableMovement (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Feedback callback for Enable Movement menu entry.
bool getArrows ()
 returns the global variable arrows_
bool getDeleted ()
 returns global variable deleted_
unsigned int getID ()
 returns id of the shape msg
visualization_msgs::MarkergetMarker ()
void getShape (cob_3d_mapping_msgs::Shape &shape)
void hideArrows (int flag_untick)
 Remove arrows for interactive marker movement.
void hideCentroid (int flag_untick)
 Remove the centroid of a shape.
void hideContour (int flag_untick)
 Remove contour of a shape.
void hideNormal (int flag_untick)
 Remove the normal vector of a shape param[in] flag_untick a flag which shows whether Enable Movement is unticked.
void hideOrigin (int flag_untick)
 Remove the origin of a cylinder.
void hideSymAxis (int flag_untick)
 Remove the Symmetry axis of a cylinder param[in] flag_untick a flag which shows whether Enable Movement is unticked.
TPPLPoint msgToPoint2D (const pcl::PointXYZ &point)
 Create menu entries for each shape.
void resetMarker ()
 Resets all controls activated for Interactive marker.
bool setArrows ()
 sets the global variable arrows_ to false
bool setDeleted ()
 sets the global variable deleted_ to false
 ShapeMarker (boost::shared_ptr< interactive_markers::InteractiveMarkerServer > im_server, cob_3d_mapping_msgs::Shape &shape, std::vector< unsigned int > &moved_shapes_indices, std::vector< unsigned int > &interacted_shapes, std::vector< unsigned int > &deleted_markers_indices, bool arrows, bool deleted)
void triangle_refinement (list< TPPLPoly > &i_list, list< TPPLPoly > &o_list)
 subdivides a list of triangles.
 ~ShapeMarker ()

Protected Attributes

bool arrows_
bool deleted_
visualization_msgs::InteractiveMarker deleted_imarker_
std::vector< unsigned int > & deleted_markers_indices_
unsigned int id_
visualization_msgs::InteractiveMarkerControl im_ctrl
boost::shared_ptr
< interactive_markers::InteractiveMarkerServer
im_server_
visualization_msgs::InteractiveMarker imarker_
std::vector< unsigned int > & interacted_shapes_
visualization_msgs::Marker marker
visualization_msgs::InteractiveMarker marker_
interactive_markers::MenuHandler menu_handler_
std::vector< unsigned int > & moved_shapes_indices_
cob_3d_mapping_msgs::Shape shape_
Eigen::Affine3f transformation_
Eigen::Affine3f transformation_inv_

Detailed Description

Definition at line 109 of file shape_marker.h.


Constructor & Destructor Documentation

ShapeMarker::ShapeMarker ( boost::shared_ptr< interactive_markers::InteractiveMarkerServer im_server,
cob_3d_mapping_msgs::Shape shape,
std::vector< unsigned int > &  moved_shapes_indices,
std::vector< unsigned int > &  interacted_shapes,
std::vector< unsigned int > &  deleted_markers_indices,
bool  arrows,
bool  deleted 
)

Definition at line 60 of file shape_marker.cpp.

ShapeMarker::~ShapeMarker (  )  [inline]

Definition at line 116 of file shape_marker.h.


Member Function Documentation

void ShapeMarker::createInteractiveMarker (  ) 

Publish interactive markers for a shape message using interactive marker server.

Definition at line 560 of file shape_marker.cpp.

void ShapeMarker::createMarker ( visualization_msgs::InteractiveMarkerControl im_ctrl  ) 

Create marker for the shape and add it to the interactive marker control.

Parameters:
[in] triangle_list triangulated list of poly points
[in] im_ctrl interactive marker control

Definition at line 350 of file shape_marker.cpp.

void ShapeMarker::createShapeMenu (  ) 

Create menu entries for each shape.

Definition at line 303 of file shape_marker.cpp.

void ShapeMarker::deleteMarker ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  ) 

feedback callback for Delete Marker menu entry

Parameters:
[in] feedback feedback from rviz when the Delete Marker menu entry of a shape is chosen

Definition at line 143 of file shape_marker.cpp.

void ShapeMarker::displayArrows (  ) 

Display arrows for interactive marker movement.

Definition at line 192 of file shape_marker.cpp.

void ShapeMarker::displayCentroid (  ) 

Display the centroid of a shape.

Definition at line 941 of file shape_marker.cpp.

void ShapeMarker::displayCentroidCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  ) 

Feedback callback for Display Centroid menu entry.

Parameters:
[in] feedback feedback from rviz when the Display Centroid menu entry of a shape is changed
feedback feedback from rviz when the Display Centroid menu entry of a shape is changed

Definition at line 918 of file shape_marker.cpp.

void ShapeMarker::displayContour (  ) 

Display contour of a shape.

Definition at line 1036 of file shape_marker.cpp.

void ShapeMarker::displayContourCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  ) 

Feedback callback for Display Contour menu entry.

Parameters:
[in] feedback feedback from rviz when the Display Contour menu entry of a shape is changed

Definition at line 1016 of file shape_marker.cpp.

void ShapeMarker::displayNormal (  ) 

Display the normal vector of a shape.

Definition at line 737 of file shape_marker.cpp.

void ShapeMarker::displayNormalCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  ) 

Feedback callback for normal menu entry.

Parameters:
[in] feedback feedback from rviz when the normal menu entry of a shape is changed

Definition at line 636 of file shape_marker.cpp.

void ShapeMarker::displayOrigin (  ) 

Display the origin of a cylinder.

Definition at line 1250 of file shape_marker.cpp.

void ShapeMarker::displayOriginCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  ) 

Feedback callback for origin menu entry.

Parameters:
[in] feedback feedback from rviz when the centroid menu entry of a shape is changed

Definition at line 1227 of file shape_marker.cpp.

void ShapeMarker::displaySymAxis (  ) 

Display the Symmetry axis of a cylinder.

Definition at line 1147 of file shape_marker.cpp.

void ShapeMarker::displaySymAxisCB ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  ) 

Feedback callback for symmetry axis menu entry with cylinders.

Parameters:
[in] feedback feedback from rviz when the symmetry axis menu entry of a shape is changed

Definition at line 1124 of file shape_marker.cpp.

void ShapeMarker::enableMovement ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr feedback  ) 

Feedback callback for Enable Movement menu entry.

Parameters:
[in] feedback feedback from rviz when the Enable Movement menu entry of a shape is changed

Definition at line 167 of file shape_marker.cpp.

bool ShapeMarker::getArrows (  ) 

returns the global variable arrows_

Parameters:
[out] global variable arrows_

Definition at line 121 of file shape_marker.cpp.

bool ShapeMarker::getDeleted (  ) 

returns global variable deleted_

Parameters:
[out] global variable deleted_

Definition at line 130 of file shape_marker.cpp.

unsigned int ShapeMarker::getID (  ) 

returns id of the shape msg

Parameters:
[out] shape msg id

Definition at line 139 of file shape_marker.cpp.

visualization_msgs::Marker& ShapeMarker::getMarker (  )  [inline]

Definition at line 285 of file shape_marker.h.

void ShapeMarker::getShape ( cob_3d_mapping_msgs::Shape shape  ) 

Definition at line 117 of file shape_marker.cpp.

void ShapeMarker::hideArrows ( int  flag_untick  ) 

Remove arrows for interactive marker movement.

Parameters:
[in] flag_untick a flag which shows whether Enable Movement is unticked

delete the arrows

deleting the Transparent Marker

end

Definition at line 248 of file shape_marker.cpp.

void ShapeMarker::hideCentroid ( int  flag_untick  ) 

Remove the centroid of a shape.

Definition at line 991 of file shape_marker.cpp.

void ShapeMarker::hideContour ( int  flag_untick  ) 

Remove contour of a shape.

Definition at line 1099 of file shape_marker.cpp.

void ShapeMarker::hideNormal ( int  flag_untick  ) 

Remove the normal vector of a shape param[in] flag_untick a flag which shows whether Enable Movement is unticked.

Definition at line 792 of file shape_marker.cpp.

void ShapeMarker::hideOrigin ( int  flag_untick  ) 

Remove the origin of a cylinder.

Definition at line 1301 of file shape_marker.cpp.

void ShapeMarker::hideSymAxis ( int  flag_untick  ) 

Remove the Symmetry axis of a cylinder param[in] flag_untick a flag which shows whether Enable Movement is unticked.

Definition at line 1203 of file shape_marker.cpp.

TPPLPoint ShapeMarker::msgToPoint2D ( const pcl::PointXYZ &  point  ) 

Create menu entries for each shape.

Parameters:
[in] point 3D point to be transformed
Returns:
returns transformed 2D TPPLPoint

Definition at line 548 of file shape_marker.cpp.

void ShapeMarker::resetMarker (  ) 

Resets all controls activated for Interactive marker.

Definition at line 286 of file shape_marker.cpp.

bool ShapeMarker::setArrows (  ) 

sets the global variable arrows_ to false

Parameters:
[out] global variable arrows_

Definition at line 125 of file shape_marker.cpp.

bool ShapeMarker::setDeleted (  ) 

sets the global variable deleted_ to false

Parameters:
[out] global variable deleted_

Definition at line 134 of file shape_marker.cpp.

void ShapeMarker::triangle_refinement ( list< TPPLPoly > &  i_list,
list< TPPLPoly > &  o_list 
)

subdivides a list of triangles.

Based on a threshold in x-Direction, triangles are subdivided.

Parameters:
[in] i_list Input triangle list.
[out] o_list Output triangle list.
Returns:
nothing

Definition at line 75 of file shape_marker.cpp.


Member Data Documentation

bool ShapeMarker::arrows_ [protected]

Definition at line 321 of file shape_marker.h.

bool ShapeMarker::deleted_ [protected]

Definition at line 322 of file shape_marker.h.

Definition at line 293 of file shape_marker.h.

std::vector<unsigned int>& ShapeMarker::deleted_markers_indices_ [protected]

Definition at line 317 of file shape_marker.h.

unsigned int ShapeMarker::id_ [protected]

Definition at line 314 of file shape_marker.h.

Definition at line 300 of file shape_marker.h.

Definition at line 302 of file shape_marker.h.

Definition at line 292 of file shape_marker.h.

std::vector<unsigned int>& ShapeMarker::interacted_shapes_ [protected]

Definition at line 316 of file shape_marker.h.

Definition at line 294 of file shape_marker.h.

Definition at line 285 of file shape_marker.h.

Definition at line 306 of file shape_marker.h.

std::vector<unsigned int>& ShapeMarker::moved_shapes_indices_ [protected]

Definition at line 315 of file shape_marker.h.

Definition at line 303 of file shape_marker.h.

Eigen::Affine3f ShapeMarker::transformation_ [protected]

Definition at line 308 of file shape_marker.h.

Eigen::Affine3f ShapeMarker::transformation_inv_ [protected]

Definition at line 309 of file shape_marker.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


cob_3d_visualization
Author(s): Georg Arbeiter
autogenerated on Fri Mar 1 15:56:22 2013