Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

VRmixin Class Reference

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

#include <VRmixin.h>

Inheritance diagram for VRmixin:

Detailed Description

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

Definition at line 37 of file VRmixin.h.

List of all members.

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 void startCrew ()
 starts map builders, pilot, and lookout
static void stopCrew ()
 stops map builders, pilot, and lookout
static void requireCrew (const std::string &memberName)
 checks to make sure Crew is instantiated
static bool isWalking ()
static bool encodeSketch (const SketchDataRoot &image)
static Sketch< ucharsketchFromSeg ()
 Import the current color-segmented camera image as a Sketch<uchar>. Must be called from doEvent().
static Sketch< ucharsketchFromChannel (const RawCameraGenerator::channel_id_t chan)
 Import channel n image as a Sketch<uchar>. Must be called from doEvent().
static Sketch< ucharsketchFromRawY ()
 Import the current y-channel camera image as a Sketch<uchar>a. Must be called from doEvent().
static Sketch< yuvsketchFromYUV ()
 Import the current camera image as a Sketch<yuv>. Must be called from doEvent().
static Sketch< usintsketchFromDepth ()
 Import the current depth image as a Sketch<usint>. Must be called from doEvent().
static std::vector< Shape
< BlobData > > 
getBlobsFromRegionGenerator (const color_index color, int minarea=25, const BlobData::BlobOrientation_t orient=BlobData::groundplane, const coordinate_t height=0, const int maxblobs=50)
 Import blobs from the current region list 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 ()
 Project shapes from cam space to ground space, uses CameraFrameOffset and Kinematics::calculateGroundPlane().
static void projectToGround (const fmat::Transform &camToBase)
 Project shapes from cam space to ground space, will assume Kinematics::calculateGroundPlane() if plane is not specified.
static void projectToGround (const fmat::Transform &camToBase, const PlaneEquation &groundplane)
static void refreshSketchWorld ()
static void refreshSketchLocal ()
static void refreshSketchCamera ()
static void autoRefreshSketchWorld ()
static void autoRefreshSketchLocal ()
static void autoRefreshSketchCamera ()

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 = NULL
 the global world mapbuilder instance
static Lookoutlookout = NULL
 the global Lookout instance
static Graspergrasper = NULL
static ShapeBasedParticleFilterparticleFilter = NULL
 the global particle filter instance
static bool isWalkingFlag = false
static bool autoRefreshWorldAllowed = true
static bool autoRefreshLocalAllowed = true
static bool autoRefreshCameraAllowed = true
static Point robotObstaclesPt = Point(0, 0, 0, allocentric)
 Used by ShapeSpacePlannerBase::addRobotObstacles to display robot body obstacles at correct point in worldShS.
static AngTwoPi robotObstaclesOri = 0
 Used by ShapeSpacePlannerBase::addRobotObstacles to display robot body obstacles at correct orientation in worldShS.
static std::vector< ShapeRootdrawShapes
 Vector of shapes to be drawn into the RawCam image.
static VisualOdometryimageOdometry = NULL

Static Protected Attributes

static unsigned int instanceCount = 0
 count of VRmixin 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 SocketcamDialogSock = NULL
 socket to talk with cam-space sketch viewer
static SocketcamSketchSock = NULL
 socket for transmitting sketch images to cam-space sketch viewer
static SocketlocalDialogSock = NULL
 socket to talk with local-space sketch viewer
static SocketlocalSketchSock = NULL
 socket for transmitting sketch images to local-space sketch viewer
static SocketworldDialogSock = NULL
 socket to talk with world-space sketch viewer
static SocketworldSketchSock = NULL
 socket for transmitting sketch images to world-space sketch viewer
static VRmixintheOne = NULL
 used so static member functions can access non-static members; works because there will always be a unique instance of VRmixin

Constructor & Destructor Documentation

VRmixin (  ) 

Constructor.

Definition at line 99 of file VRmixin.cc.

~VRmixin ( void   )  [virtual]

Destructor.

Definition at line 154 of file VRmixin.cc.

VRmixin ( const VRmixin  )  [private]

never call this


Member Function Documentation

void autoRefreshSketchCamera (  )  [static]

Definition at line 299 of file VRmixin.cc.

void autoRefreshSketchLocal (  )  [static]

Definition at line 294 of file VRmixin.cc.

void autoRefreshSketchWorld (  )  [static]

Definition at line 289 of file VRmixin.cc.

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

Called whenever data is received on camDialogSocket.

Definition at line 304 of file VRmixin.cc.

Referenced by VRmixin::VRmixin().

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

Definition at line 342 of file VRmixin.cc.

Referenced by VRmixin::processSketchRequest().

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

Import blobs from the current region list as a vector of Shape<BlobData>

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

Definition at line 436 of file VRmixin.cc.

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 44 of file VRmixin.cc.

Referenced by VRmixin::getGroundShS().

ShapeSpace & getGroundShS (  )  [static]

Definition at line 53 of file VRmixin.cc.

SketchSpace & getLocalSkS (  )  [static]

Definition at line 47 of file VRmixin.cc.

SketchSpace & getWorldSkS (  )  [static]

Definition at line 50 of file VRmixin.cc.

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

Called whenever data is received on localDialogSocket.

Definition at line 310 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 457 of file VRmixin.cc.

Referenced by VRmixin::dialogCallback().

void projectToGround ( const fmat::Transform camToBase,
const PlaneEquation groundplane 
) [static]

Definition at line 266 of file VRmixin.cc.

void projectToGround ( const fmat::Transform camToBase  )  [static]

Project shapes from cam space to ground space, will assume Kinematics::calculateGroundPlane() if plane is not specified.

Definition at line 262 of file VRmixin.cc.

void projectToGround (  )  [static]

Project shapes from cam space to ground space, uses CameraFrameOffset and Kinematics::calculateGroundPlane().

Definition at line 257 of file VRmixin.cc.

Referenced by VRmixin::projectToGround().

void refreshSketchCamera (  )  [static]

Definition at line 284 of file VRmixin.cc.

Referenced by VRmixin::autoRefreshSketchCamera().

void refreshSketchLocal (  )  [static]

Definition at line 279 of file VRmixin.cc.

Referenced by VRmixin::autoRefreshSketchLocal().

void refreshSketchWorld (  )  [static]

Definition at line 274 of file VRmixin.cc.

Referenced by VRmixin::autoRefreshSketchWorld().

void requireCrew ( const std::string &  memberName  )  [static]

checks to make sure Crew is instantiated

Definition at line 250 of file VRmixin.cc.

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

Import channel n image as a Sketch<uchar>. Must be called from doEvent().

Import channel n as a Sketch<uchar>

Definition at line 364 of file VRmixin.cc.

Referenced by VRmixin::sketchFromRawY().

Sketch< usint > sketchFromDepth (  )  [static]

Import the current depth image as a Sketch<usint>. Must be called from doEvent().

Definition at line 390 of file VRmixin.cc.

Sketch< uchar > sketchFromRawY (  )  [static]

Import the current y-channel camera image as a Sketch<uchar>a. Must be called from doEvent().

Definition at line 386 of file VRmixin.cc.

Sketch< uchar > sketchFromSeg (  )  [static]

Import the current color-segmented camera image as a Sketch<uchar>. Must be called from doEvent().

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

Definition at line 354 of file VRmixin.cc.

Referenced by TargetData::extractLineTarget().

Sketch< yuv > sketchFromYUV (  )  [static]

Import the current camera image as a Sketch<yuv>. Must be called from doEvent().

Definition at line 407 of file VRmixin.cc.

void startCrew (  )  [static]

starts map builders, pilot, and lookout

Definition at line 202 of file VRmixin.cc.

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

void stopCrew (  )  [static]

stops map builders, pilot, and lookout

Definition at line 230 of file VRmixin.cc.

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

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

Called whenever data is received on worldDialogSocket.

Definition at line 316 of file VRmixin.cc.

Referenced by VRmixin::VRmixin().


Member Data Documentation

bool autoRefreshCameraAllowed = true [static]

Definition at line 135 of file VRmixin.h.

Referenced by VRmixin::autoRefreshSketchCamera().

bool autoRefreshLocalAllowed = true [static]

Definition at line 134 of file VRmixin.h.

Referenced by VRmixin::autoRefreshSketchLocal().

bool autoRefreshWorldAllowed = true [static]

Definition at line 133 of file VRmixin.h.

Referenced by VRmixin::autoRefreshSketchWorld().

Socket * camDialogSock = NULL [static, private]

socket to talk with cam-space sketch viewer

Definition at line 74 of file VRmixin.h.

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

Socket * camSketchSock = NULL [static, private]

socket for transmitting sketch images to cam-space sketch viewer

Definition at line 75 of file VRmixin.h.

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

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 40 of file VRmixin.h.

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

std::vector< ShapeRoot > drawShapes [static]

Vector of shapes to be drawn into the RawCam image.

Definition at line 149 of file VRmixin.h.

Referenced by VRmixin::~VRmixin().

Grasper * grasper = NULL [static]

Definition at line 67 of file VRmixin.h.

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

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

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

Definition at line 52 of file VRmixin.h.

Referenced by VRmixin::projectToGround().

VisualOdometry * imageOdometry = NULL [static]

Definition at line 151 of file VRmixin.h.

Referenced by VRmixin::stopCrew().

unsigned int instanceCount = 0 [static, protected]

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

Definition at line 39 of file VRmixin.h.

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

bool isWalkingFlag = false [static]

Definition at line 71 of file VRmixin.h.

Socket * localDialogSock = NULL [static, private]

socket to talk with local-space sketch viewer

Definition at line 76 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 55 of file VRmixin.h.

Referenced by AgentData::findAgentsBelt(), VRmixin::localDialogSockCallback(), VRmixin::startCrew(), and VRmixin::~VRmixin().

Socket * localSketchSock = NULL [static, private]

socket for transmitting sketch images to local-space sketch viewer

Definition at line 77 of file VRmixin.h.

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

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

The localmap sketch space (LocalMapBuilder::localSkS).

Definition at line 54 of file VRmixin.h.

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

Lookout * lookout = NULL [static]

the global Lookout instance

Definition at line 62 of file VRmixin.h.

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

MapBuilder * mapBuilder = NULL [static]

the global particle filter instance

Definition at line 70 of file VRmixin.h.

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

Used by ShapeSpacePlannerBase::addRobotObstacles to display robot body obstacles at correct orientation in worldShS.

Definition at line 147 of file VRmixin.h.

Point robotObstaclesPt = Point(0, 0, 0, allocentric) [static]

Used by ShapeSpacePlannerBase::addRobotObstacles to display robot body obstacles at correct point in worldShS.

Definition at line 144 of file VRmixin.h.

Shape< AgentData > theAgent [static]

The robot (usually lives in worldShS).

Definition at line 59 of file VRmixin.h.

Referenced by ShapeSpace::clear(), AgentData::findAgentsBelt(), Point::isLeftOf(), VRmixin::VRmixin(), and VRmixin::~VRmixin().

VRmixin * theOne = NULL [static, private]

used so static member functions can access non-static members; works because there will always be a unique instance of VRmixin

Definition at line 155 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 78 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 58 of file VRmixin.h.

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

Socket * worldSketchSock = NULL [static, private]

socket for transmitting sketch images to world-space sketch viewer

Definition at line 79 of file VRmixin.h.

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

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

The worldmap sketch space (WorldMapBuilder::localSkS).

Definition at line 57 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 5.1CVS
Generated Mon May 9 04:56:32 2016 by Doxygen 1.6.3