Public Member Functions | Protected Member Functions | Protected Attributes
srs_interaction_primitives::Primitive Class Reference

#include <primitive.h>

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

List of all members.

Public Member Functions

void changeColor (std_msgs::ColorRGBA color)
 Change primitive's color.
virtual void defaultCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Default callback for objects.
virtual void erase ()
 Erase primitive from Interactive Marker Server.
std_msgs::ColorRGBA getColor ()
 Gets primitive's color.
visualization_msgs::InteractiveMarkerControl * getControl (std::string name)
 Returns control.
std::string getDescription ()
std::string getFrameID ()
 Gets primitive's fixed frame.
std::string getName ()
 Gets primitive's name.
geometry_msgs::Pose getPose ()
 Gets primitive's position and orientation.
int getPoseType ()
 Gets the way to set the pose.
int getPrimitiveType ()
 Gets type of this primitive.
geometry_msgs::Vector3 getScale ()
 Gets primitive's scale.
std::string getUpdateTopic (int update_type)
 Gets update topic.
virtual void insert ()
 Insert primitive into Interactive Marker Server.
 Primitive (InteractiveMarkerServerPtr server, std::string frame_id, std::string name, int type)
 Constructor.
 Primitive ()
 Constructor.
void setColor (std_msgs::ColorRGBA color)
 Sets color of the primitive.
void setDescription (std::string description)
 Sets description to object.
void setFrameID (std::string frame_id)
 Sets fixed frame to object.
void setPose (geometry_msgs::Pose pose)
 Sets position and orientation to object.
void setPoseType (int type)
 Sets the way to set the pose.
void setPrimitiveType (int type)
 Sets type of this primitive.
void setScale (geometry_msgs::Vector3 scale)
 Sets scale to object.
void updateControls ()
 Updates visible controls.
virtual ~Primitive ()
 Destructor.

Protected Member Functions

void addDescriptionControl ()
 Adds description controls.
void addMeasureControl ()
 Adds measure controls.
void addMovementControls ()
 Adds movement controls.
void addRotationControls ()
 Adds rotation controls.
void addScaleControls ()
 Adds scale controls.
void clearObject ()
 Resets object.
virtual void create ()
 Create Object.
virtual void createMenu ()
 Create menu.
void removeControl (std::string name)
void removeDescriptionControl ()
void removeMeasureControl ()
 Removes measure control.
void removeMovementControls ()
 Removes movement controls.
void removeRotationControls ()
 Removes rotation controls.
void removeScaleControls ()
 Removes scale controls.
void scaleFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Scale controls feedback.
virtual void updateScaleControls ()
 Updates scale controls.

Protected Attributes

std_msgs::ColorRGBA color_
std_msgs::ColorRGBA color_green_a01_
visualization_msgs::InteractiveMarkerControl control_
std::string description_
visualization_msgs::InteractiveMarkerControl descriptionControl_
tf::StampedTransform feedbackToDefaultTransform
std::string frame_id_
geometry_msgs::Vector3 max_size_
visualization_msgs::InteractiveMarkerControl measureControl_
bool menu_created_
interactive_markers::MenuHandler menu_handler_
geometry_msgs::Vector3 min_size_
visualization_msgs::InteractiveMarkerControl moveXControl_
visualization_msgs::InteractiveMarkerControl moveYControl_
visualization_msgs::InteractiveMarkerControl moveZControl_
std::string name_
visualization_msgs::InteractiveMarker object_
geometry_msgs::Pose pose_
geometry_msgs::Pose pose_change
int pose_type_
int primitive_type_
visualization_msgs::InteractiveMarkerControl rotateXControl_
visualization_msgs::InteractiveMarkerControl rotateYControl
visualization_msgs::InteractiveMarkerControl rotateZControl_
geometry_msgs::Vector3 scale_
geometry_msgs::Vector3 scale_prev_
int scale_saved_
visualization_msgs::InteractiveMarkerControl scaleControl_
InteractiveMarkerServerPtr server_
bool show_description_control_
bool show_measure_control_
bool show_movement_control_
bool show_rotation_control_
bool show_scale_control_
bool show_trajectory_control_
tf::TransformListenertfListener
visualization_msgs::InteractiveMarkerControl trajectoryControl_
tf::Transformer transformer
UpdatePublisherupdatePublisher_

Detailed Description

This class is parent class for BUT GUI primitives

Author:
Tomas Lokaj

Definition at line 86 of file primitive.h.


Constructor & Destructor Documentation

srs_interaction_primitives::Primitive::Primitive ( InteractiveMarkerServerPtr  server,
std::string  frame_id,
std::string  name,
int  type 
)

Constructor.

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

Constructor.

Definition at line 100 of file primitive.h.

Destructor.

Definition at line 107 of file primitive.h.


Member Function Documentation

Adds description controls.

Definition at line 532 of file primitive.cpp.

Adds measure controls.

Definition at line 433 of file primitive.cpp.

Adds movement controls.

Parameters:
markeris Interactive marker

Definition at line 336 of file primitive.cpp.

Adds rotation controls.

Definition at line 369 of file primitive.cpp.

Adds scale controls.

Definition at line 573 of file primitive.cpp.

void srs_interaction_primitives::Primitive::changeColor ( std_msgs::ColorRGBA  color)

Change primitive's color.

Parameters:
coloris primitives's color

Definition at line 704 of file primitive.cpp.

Resets object.

Definition at line 697 of file primitive.cpp.

virtual void srs_interaction_primitives::Primitive::create ( ) [inline, protected, virtual]
virtual void srs_interaction_primitives::Primitive::createMenu ( ) [inline, protected, virtual]
void srs_interaction_primitives::Primitive::defaultCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [virtual]

Default callback for objects.

Definition at line 60 of file primitive.cpp.

Erase primitive from Interactive Marker Server.

Definition at line 328 of file primitive.cpp.

std_msgs::ColorRGBA srs_interaction_primitives::Primitive::getColor ( ) [inline]

Gets primitive's color.

Returns:
primitive's color

Definition at line 201 of file primitive.h.

InteractiveMarkerControl * srs_interaction_primitives::Primitive::getControl ( std::string  name)

Returns control.

Parameters:
nameis controls name

Definition at line 313 of file primitive.cpp.

Gets primitive's description

Returns:
primitive's description

Definition at line 282 of file primitive.h.

Gets primitive's fixed frame.

Returns:
primitive's fixed frame

Definition at line 300 of file primitive.h.

std::string srs_interaction_primitives::Primitive::getName ( void  ) [inline]

Gets primitive's name.

Returns:
primitive's name

Definition at line 183 of file primitive.h.

Gets primitive's position and orientation.

Returns:
primitive's position and orientation

Definition at line 234 of file primitive.h.

Gets the way to set the pose.

Returns:
type of the pose

Definition at line 145 of file primitive.h.

Gets type of this primitive.

Returns:
primitives type

Definition at line 165 of file primitive.h.

geometry_msgs::Vector3 srs_interaction_primitives::Primitive::getScale ( ) [inline]

Gets primitive's scale.

Returns:
primitive's scale

Definition at line 264 of file primitive.h.

std::string srs_interaction_primitives::Primitive::getUpdateTopic ( int  update_type) [inline]

Gets update topic.

Parameters:
update_typeis update's type

Definition at line 174 of file primitive.h.

void srs_interaction_primitives::Primitive::removeControl ( std::string  name) [protected]

Removes control with specified name

Parameters:
nameis control's name

Definition at line 418 of file primitive.cpp.

Removes description control

Definition at line 526 of file primitive.cpp.

Removes measure control.

Definition at line 520 of file primitive.cpp.

Removes movement controls.

Definition at line 402 of file primitive.cpp.

Removes rotation controls.

Definition at line 410 of file primitive.cpp.

Removes scale controls.

Definition at line 562 of file primitive.cpp.

void srs_interaction_primitives::Primitive::scaleFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Scale controls feedback.

Definition at line 160 of file primitive.cpp.

void srs_interaction_primitives::Primitive::setColor ( std_msgs::ColorRGBA  color) [inline]

Sets color of the primitive.

Parameters:
coloris primitive's color

Definition at line 192 of file primitive.h.

void srs_interaction_primitives::Primitive::setDescription ( std::string  description) [inline]

Sets description to object.

Parameters:
descriptionis primitive's description

Definition at line 273 of file primitive.h.

void srs_interaction_primitives::Primitive::setFrameID ( std::string  frame_id) [inline]

Sets fixed frame to object.

Parameters:
frame_idis primitive's fixed frame

Definition at line 291 of file primitive.h.

Sets position and orientation to object.

Parameters:
poseis primitive's position and orientation

Definition at line 210 of file primitive.h.

Sets the way to set the pose.

Parameters:
typeof the pose

Definition at line 133 of file primitive.h.

Sets type of this primitive.

Parameters:
typeis primitive's type

Definition at line 154 of file primitive.h.

void srs_interaction_primitives::Primitive::setScale ( geometry_msgs::Vector3  scale) [inline]

Sets scale to object.

Parameters:
scaleis primitive's scale

Definition at line 243 of file primitive.h.

Updates visible controls.

Reimplemented in srs_interaction_primitives::Object, and srs_interaction_primitives::Billboard.

Definition at line 669 of file primitive.cpp.

Updates scale controls.

Definition at line 637 of file primitive.cpp.


Member Data Documentation

std_msgs::ColorRGBA srs_interaction_primitives::Primitive::color_ [protected]

Definition at line 431 of file primitive.h.

Definition at line 431 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::control_ [protected]

Definition at line 411 of file primitive.h.

Definition at line 427 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::descriptionControl_ [protected]

Definition at line 411 of file primitive.h.

Definition at line 424 of file primitive.h.

Definition at line 427 of file primitive.h.

geometry_msgs::Vector3 srs_interaction_primitives::Primitive::max_size_ [protected]

Definition at line 408 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::measureControl_ [protected]

Definition at line 411 of file primitive.h.

Definition at line 439 of file primitive.h.

Definition at line 415 of file primitive.h.

geometry_msgs::Vector3 srs_interaction_primitives::Primitive::min_size_ [protected]

Definition at line 408 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::moveXControl_ [protected]

Definition at line 413 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::moveYControl_ [protected]

Definition at line 413 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::moveZControl_ [protected]

Definition at line 413 of file primitive.h.

Definition at line 427 of file primitive.h.

visualization_msgs::InteractiveMarker srs_interaction_primitives::Primitive::object_ [protected]

Definition at line 410 of file primitive.h.

Definition at line 429 of file primitive.h.

Definition at line 433 of file primitive.h.

Definition at line 432 of file primitive.h.

Definition at line 409 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::rotateXControl_ [protected]

Definition at line 413 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::rotateYControl [protected]

Definition at line 413 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::rotateZControl_ [protected]

Definition at line 413 of file primitive.h.

geometry_msgs::Vector3 srs_interaction_primitives::Primitive::scale_ [protected]

Definition at line 430 of file primitive.h.

geometry_msgs::Vector3 srs_interaction_primitives::Primitive::scale_prev_ [protected]

Definition at line 441 of file primitive.h.

Definition at line 442 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::scaleControl_ [protected]

Definition at line 411 of file primitive.h.

Definition at line 428 of file primitive.h.

Definition at line 437 of file primitive.h.

Definition at line 437 of file primitive.h.

Definition at line 437 of file primitive.h.

Definition at line 437 of file primitive.h.

Definition at line 437 of file primitive.h.

Definition at line 437 of file primitive.h.

Definition at line 418 of file primitive.h.

visualization_msgs::InteractiveMarkerControl srs_interaction_primitives::Primitive::trajectoryControl_ [protected]

Definition at line 411 of file primitive.h.

Definition at line 421 of file primitive.h.

Definition at line 435 of file primitive.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