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

#include <billboard.h>

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

List of all members.

Public Member Functions

void addTrajectoryControls ()
 Adds trajectory controls.
 Billboard (InteractiveMarkerServerPtr server, std::string frame_id, std::string name)
geometry_msgs::Quaternion getDirection ()
 Gets billboard's movement direction.
int getType ()
double getVelocity ()
 Gets billboard's movement velocity.
void insert ()
void menuCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &)
void removeTrajectoryControls ()
 Removes trajectory control.
void setDirection (geometry_msgs::Quaternion direction)
 Sets direction to the billboard.
void setType (int type)
void setVelocity (double velocity)
 Sets velocity to the billboard.
void updateControls ()
 Updates visible controls.

Private Member Functions

void addTrajectoryPredictionMarkers ()
void create ()
 Create Object.
void createMenu ()
 Create menu.
void createMesh ()
void removeTrajectoryPredictionMarkers ()

Private Attributes

int billboard_type_
geometry_msgs::Quaternion direction_
visualization_msgs::Marker mesh_
double velocity_

Detailed Description

This class represents Billboard primitive.

Billboard represents real world object detected around robot, which is hard to describe with some mesh. Billboard is view facing and iẗ́'s types are specified in srs_env_model/BillboardType message. Billboard can also illustrate the movement of the represented object, e.g., walking person.

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

Definition at line 53 of file billboard.h.


Constructor & Destructor Documentation

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

Constructor.

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

Definition at line 39 of file billboard.cpp.


Member Function Documentation

Adds trajectory controls.

Definition at line 139 of file billboard.cpp.

Definition at line 226 of file billboard.cpp.

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

Create Object.

Reimplemented from srs_interaction_primitives::Primitive.

Definition at line 299 of file billboard.cpp.

Create menu.

Reimplemented from srs_interaction_primitives::Primitive.

Definition at line 185 of file billboard.cpp.

Definition at line 203 of file billboard.cpp.

geometry_msgs::Quaternion srs_interaction_primitives::Billboard::getDirection ( ) [inline]

Gets billboard's movement direction.

Returns:
billboard's movement direction

Definition at line 119 of file billboard.h.

Gets billboard's type

Returns:
type of the billboard

Definition at line 118 of file billboard.cpp.

Gets billboard's movement velocity.

Returns:
billboard's movement velocity

Definition at line 85 of file billboard.h.

Inserts this billboard into Interactive marker server

Reimplemented from srs_interaction_primitives::Primitive.

Definition at line 322 of file billboard.cpp.

void srs_interaction_primitives::Billboard::menuCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  )

Callback for menu

Definition at line 49 of file billboard.cpp.

Removes trajectory control.

Definition at line 133 of file billboard.cpp.

Definition at line 288 of file billboard.cpp.

void srs_interaction_primitives::Billboard::setDirection ( geometry_msgs::Quaternion  direction) [inline]

Sets direction to the billboard.

Parameters:
directionis billboard's direction

Definition at line 96 of file billboard.h.

Sets type to the billboard

Parameters:
typeis billboard's type

Definition at line 113 of file billboard.cpp.

void srs_interaction_primitives::Billboard::setVelocity ( double  velocity) [inline]

Sets velocity to the billboard.

Parameters:
velocityis billboard's velocity

Definition at line 130 of file billboard.h.

Updates visible controls.

Reimplemented from srs_interaction_primitives::Primitive.

Definition at line 123 of file billboard.cpp.


Member Data Documentation

Definition at line 165 of file billboard.h.

geometry_msgs::Quaternion srs_interaction_primitives::Billboard::direction_ [private]

Definition at line 164 of file billboard.h.

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

Definition at line 166 of file billboard.h.

Definition at line 163 of file billboard.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