Homepage Demos Overview Downloads Tutorials Reference
Credits

VRmixin Class Reference

#include <VRmixin.h>

Inheritance diagram for VRmixin:

Inheritance graph
[legend]
List of all members.

Detailed Description

Mix-in for the BehaviorBase or StateNode class to give access to VisualRoutinesBehavior variables.

Definition at line 33 of file VRmixin.h.

Public Member Functions

 VRmixin ()
 Constructor.
virtual ~VRmixin (void)
 Destructor.

Static Public Member Functions

static SketchSpacegetCamSkS ()
 returns reference to the global space instances, call there from global constructors instead of accessing camSkS, which might not be initialized yet
static SketchSpacegetLocalSkS ()
static SketchSpacegetWorldSkS ()
static ShapeSpacegetGroundShS ()
static MapBuildergetMapBuilder ()
 returns reference to the global WorldMapBuilder instance, call this from global constructors instead of accessing worldmap or localmap, which might not be initialized yet
static void startCrew ()
 starts map builders, pilot, and lookout
static void stopCrew ()
 stops map builders, pilot, and lookout
static bool rleEncodeSketch (const SketchDataRoot &image)
static Sketch< ucharsketchFromSeg ()
 Import a color-segmented image as a Sketch<uchar>.
static Sketch< ucharsketchFromChannel (RawCameraGenerator::channel_id_t chan)
 Import channel n as a Sketch<uchar>.
static Sketch< ucharsketchFromRawY ()
 Import the current y-channel camera image as a Sketch<uchar>.
static std::vector< Shape<
BlobData > > 
getBlobsFromRegionGenerator (int color, int minarea=0, BlobData::BlobOrientation_t orient=BlobData::groundplane, int maxblobs=50)
 Import the results of the region generator as a vector of Shape<BlobData>.
static void processSketchRequest (const std::string &line, SketchSpace &sketches, ShapeSpace &shapes)
 processes a single line of input for a Sketch request
static void projectToGround (const NEWMAT::Matrix &camToBase=kine->jointToBase(CameraFrameOffset), const NEWMAT::ColumnVector &ground_plane=kine->calculateGroundPlane())
 project shapes from cam space to ground space

Static Public Attributes

static SketchSpacecamSkS = VRmixin::getCamSkS()
 The camera sketch space.
static ShapeSpacecamShS = VRmixin::getCamSkS().getDualSpace()
 The camera shape space.
static ShapeSpacegroundShS = VRmixin::getGroundShS()
 The ground shape space of MapBuilder (MapBuilder::groundShS).
static SketchSpacelocalSkS = VRmixin::getLocalSkS()
 The localmap sketch space (LocalMapBuilder::localSkS).
static ShapeSpacelocalShS = VRmixin::getLocalSkS().getDualSpace()
 The localmap shape space (LocalMapBuilder::localShS).
static SketchSpaceworldSkS = VRmixin::getWorldSkS()
 The worldmap sketch space (WorldMapBuilder::localSkS).
static ShapeSpaceworldShS = VRmixin::getWorldSkS().getDualSpace()
 The worldmap sketch space (WorldMapBuilder::localShS).
static Shape< AgentDatatheAgent
 The robot (usually lives in worldShS).
static MapBuildermapBuilder = VRmixin::getMapBuilder()
 the global world mapbuilder instance
static Pilot pilot
 the global Pilot instance
static Lookout lookout
 the global Lookout instance
static ParticleFilter filter
 particle filter for localization

Static Protected Attributes

static unsigned int instanceCount = 0
 count of NewVRmixin instances -- when this hits zero, free sketch spaces
static unsigned int crewCount = 0
 count of "crew" (pilot, lookout, map builders) users -- stop these when no one is using them

Private Member Functions

 VRmixin (const VRmixin &)
 never call this
VRmixinoperator= (const VRmixin &)
 never call this

Static Private Member Functions

static int camDialogSockCallback (char *buf, int bytes)
 Called whenever data is received on camDialogSocket.
static int localDialogSockCallback (char *buf, int bytes)
 Called whenever data is received on localDialogSocket.
static int worldDialogSockCallback (char *buf, int bytes)
 Called whenever data is received on worldDialogSocket.
static void dialogCallback (char *buf, int bytes, std::string &incomplete, SketchSpace &SkS, ShapeSpace &ShS)

Static Private Attributes

static Socket * camDialogSock = NULL
 socket to talk with cam-space sketch viewer
static Socket * camRleSock = NULL
 socket for transmitting RLE images to cam-space sketch viewer
static Socket * localDialogSock = NULL
 socket to talk with local-space sketch viewer
static Socket * localRleSock = NULL
 socket for transmitting RLE images to local-space sketch viewer
static Socket * worldDialogSock = NULL
 socket to talk with world-space sketch viewer
static Socket * worldRleSock = NULL
 socket for transmitting RLE images to world-space sketch viewer
static VRmixintheOne = NULL
 used so static member functions can access non-static members


Constructor & Destructor Documentation

VRmixin (  ) 

Constructor.

Definition at line 82 of file VRmixin.cc.

~VRmixin ( void   )  [virtual]

Destructor.

Definition at line 135 of file VRmixin.cc.

VRmixin ( const VRmixin  )  [private]

never call this


Member Function Documentation

int camDialogSockCallback ( char *  buf,
int  bytes 
) [static, private]

Called whenever data is received on camDialogSocket.

Definition at line 210 of file VRmixin.cc.

Referenced by VRmixin::VRmixin().

void dialogCallback ( char *  buf,
int  bytes,
std::string &  incomplete,
SketchSpace SkS,
ShapeSpace ShS 
) [static, private]

vector< Shape< BlobData > > getBlobsFromRegionGenerator ( int  color,
int  minarea = 0,
BlobData::BlobOrientation_t  orient = BlobData::groundplane,
int  maxblobs = 50 
) [static]

Import the results of the region generator as a vector of Shape<BlobData>.

Definition at line 301 of file VRmixin.cc.

Referenced by MapBuilder::getCamBlobs().

SketchSpace & getCamSkS (  )  [static]

returns reference to the global space instances, call there from global constructors instead of accessing camSkS, which might not be initialized yet

Definition at line 34 of file VRmixin.cc.

Referenced by VRmixin::getGroundShS().

ShapeSpace & getGroundShS (  )  [static]

Definition at line 43 of file VRmixin.cc.

SketchSpace & getLocalSkS (  )  [static]

Definition at line 37 of file VRmixin.cc.

MapBuilder & getMapBuilder (  )  [static]

returns reference to the global WorldMapBuilder instance, call this from global constructors instead of accessing worldmap or localmap, which might not be initialized yet

Definition at line 48 of file VRmixin.cc.

SketchSpace & getWorldSkS (  )  [static]

Definition at line 40 of file VRmixin.cc.

int localDialogSockCallback ( char *  buf,
int  bytes 
) [static, private]

Called whenever data is received on localDialogSocket.

Definition at line 216 of file VRmixin.cc.

Referenced by VRmixin::VRmixin().

VRmixin& operator= ( const VRmixin  )  [private]

never call this

void processSketchRequest ( const std::string &  line,
SketchSpace sketches,
ShapeSpace shapes 
) [static]

processes a single line of input for a Sketch request

Definition at line 319 of file VRmixin.cc.

Referenced by VRmixin::dialogCallback().

void projectToGround ( const NEWMAT::Matrix &  camToBase = kine->jointToBase(CameraFrameOffset),
const NEWMAT::ColumnVector &  ground_plane = kine->calculateGroundPlane() 
) [static]

project shapes from cam space to ground space

Definition at line 201 of file VRmixin.cc.

Referenced by MapBuilder::projectToGround().

bool rleEncodeSketch ( const SketchDataRoot image  )  [static]

Definition at line 247 of file VRmixin.cc.

Referenced by VRmixin::processSketchRequest().

Sketch< uchar > sketchFromChannel ( RawCameraGenerator::channel_id_t  chan  )  [static]

Import channel n as a Sketch<uchar>.

Definition at line 270 of file VRmixin.cc.

Referenced by VRmixin::sketchFromRawY().

Sketch< uchar > sketchFromRawY (  )  [static]

Import the current y-channel camera image as a Sketch<uchar>.

Definition at line 294 of file VRmixin.cc.

Sketch< uchar > sketchFromSeg (  )  [static]

Import a color-segmented image as a Sketch<uchar>.

Definition at line 259 of file VRmixin.cc.

void startCrew (  )  [static]

starts map builders, pilot, and lookout

Definition at line 180 of file VRmixin.cc.

Referenced by VisualRoutinesStateNode::DoStart(), and VisualRoutinesBehavior::DoStart().

void stopCrew (  )  [static]

stops map builders, pilot, and lookout

Definition at line 192 of file VRmixin.cc.

Referenced by VisualRoutinesStateNode::DoStop(), and VisualRoutinesBehavior::DoStop().

int worldDialogSockCallback ( char *  buf,
int  bytes 
) [static, private]

Called whenever data is received on worldDialogSocket.

Definition at line 222 of file VRmixin.cc.

Referenced by VRmixin::VRmixin().


Member Data Documentation

Socket * camDialogSock = NULL [static, private]

socket to talk with cam-space sketch viewer

Definition at line 66 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), and VRmixin::~VRmixin().

Socket * camRleSock = NULL [static, private]

socket for transmitting RLE images to cam-space sketch viewer

Definition at line 67 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), and VRmixin::~VRmixin().

ShapeSpace & camShS = VRmixin::getCamSkS().getDualSpace() [static]

unsigned int crewCount = 0 [static, protected]

count of "crew" (pilot, lookout, map builders) users -- stop these when no one is using them

Definition at line 36 of file VRmixin.h.

Referenced by VRmixin::startCrew(), and VRmixin::stopCrew().

particle filter for localization

Definition at line 63 of file VRmixin.h.

Referenced by VRmixin::~VRmixin().

ShapeSpace & groundShS = VRmixin::getGroundShS() [static]

The ground shape space of MapBuilder (MapBuilder::groundShS).

Definition at line 51 of file VRmixin.h.

Referenced by MapBuilder::formBoundingBox(), MapBuilder::isLineVisible(), and VRmixin::projectToGround().

unsigned int instanceCount = 0 [static, protected]

count of NewVRmixin instances -- when this hits zero, free sketch spaces

Definition at line 35 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), and VRmixin::~VRmixin().

Socket * localDialogSock = NULL [static, private]

socket to talk with local-space sketch viewer

Definition at line 68 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), and VRmixin::~VRmixin().

Socket * localRleSock = NULL [static, private]

socket for transmitting RLE images to local-space sketch viewer

Definition at line 69 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), and VRmixin::~VRmixin().

ShapeSpace & localShS = VRmixin::getLocalSkS().getDualSpace() [static]

The localmap shape space (LocalMapBuilder::localShS).

Definition at line 54 of file VRmixin.h.

Referenced by VRmixin::localDialogSockCallback(), and VRmixin::~VRmixin().

SketchSpace & localSkS = VRmixin::getLocalSkS() [static]

The localmap sketch space (LocalMapBuilder::localSkS).

Definition at line 53 of file VRmixin.h.

Referenced by VRmixin::localDialogSockCallback(), VRmixin::VRmixin(), and VRmixin::~VRmixin().

MapBuilder & mapBuilder = VRmixin::getMapBuilder() [static]

the global world mapbuilder instance

Definition at line 60 of file VRmixin.h.

Referenced by VRmixin::startCrew(), VRmixin::stopCrew(), and VRmixin::VRmixin().

Pilot pilot [static]

the global Pilot instance

Definition at line 61 of file VRmixin.h.

Referenced by VRmixin::startCrew(), VRmixin::stopCrew(), and VRmixin::VRmixin().

Shape< AgentData > theAgent [static]

The robot (usually lives in worldShS).

Definition at line 58 of file VRmixin.h.

Referenced by ShapeSpace::clear(), and VRmixin::VRmixin().

VRmixin * theOne = NULL [static, private]

used so static member functions can access non-static members

Definition at line 112 of file VRmixin.h.

Referenced by VRmixin::camDialogSockCallback(), VRmixin::dialogCallback(), VRmixin::localDialogSockCallback(), VRmixin::VRmixin(), VRmixin::worldDialogSockCallback(), and VRmixin::~VRmixin().

Socket * worldDialogSock = NULL [static, private]

socket to talk with world-space sketch viewer

Definition at line 70 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), and VRmixin::~VRmixin().

Socket * worldRleSock = NULL [static, private]

socket for transmitting RLE images to world-space sketch viewer

Definition at line 71 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), and VRmixin::~VRmixin().

ShapeSpace & worldShS = VRmixin::getWorldSkS().getDualSpace() [static]

The worldmap sketch space (WorldMapBuilder::localShS).

Definition at line 57 of file VRmixin.h.

Referenced by PathPlanner::addLandmark(), ShapeSpace::clear(), VRmixin::VRmixin(), VRmixin::worldDialogSockCallback(), and VRmixin::~VRmixin().

SketchSpace & worldSkS = VRmixin::getWorldSkS() [static]

The worldmap sketch space (WorldMapBuilder::localSkS).

Definition at line 56 of file VRmixin.h.

Referenced by VRmixin::VRmixin(), VRmixin::worldDialogSockCallback(), and VRmixin::~VRmixin().


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

DualCoding 3.0beta
Generated Wed Oct 4 00:02:31 2006 by Doxygen 1.4.7