constraint_app
ConstraintApp Class Reference

#include <ConstraintApp.h>

Inheritance diagram for ConstraintApp:
ConstraintApp_MB

List of all members.

Public Types

typedef boost::optional
< KDL::Frame > 
OptionalKDLFrame

Public Member Functions

 ConstraintApp ()
virtual ~ConstraintApp ()
virtual bool WaitForObservations (unsigned int timeout_ms)=0
virtual bool GetObservations (std::vector< double > &actualObservations, std::vector< std::string > &observationIds)=0
virtual bool GetExpectedObservations (const std::vector< double > &state, const std::vector< std::string > &observationIds, std::vector< double > &observations)=0
virtual bool GetResetAndClear ()=0
virtual void GetCurrentStateEstimate (std::vector< double > &state)=0
virtual void SetCurrentStateEstimate (const std::vector< double > &state)=0
virtual void AffordanceTrackCollectionHandlerAux (const lcm::ReceiveBuffer *rbuf, const std::string &channel, const drc::affordance_track_collection_t *tracks)
virtual void AffordanceTrackCollectionHandler (const drc::affordance_track_collection_t *affordance)=0
virtual void AffordanceFitHandlerAux (const lcm::ReceiveBuffer *rbuf, const std::string &channel, const drc::affordance_plus_t *affordance)
virtual void AffordanceFitHandler (const drc::affordance_plus_t *affordance)=0
virtual int GetStateSize ()=0

Static Public Member Functions

static OptionalKDLFrame GetFrameFromParams (const drc::affordance_t *msg)
static std::vector< double > FrameToVector (const KDL::Frame &frame)
static KDL::Frame VectorToFrame (const std::vector< double > &state)

Protected Member Functions

bool shouldStop ()
void stopThreads ()
void main ()
int lcm_handle_timeout (lcm_t *lcm, int ms)

Protected Attributes

boost::thread * m_mainThread
volatile bool m_stopThreads
boost::mutex m_stopThreadsMutex
boost::mutex m_lcmMutex
lcm::LCM * m_lcm
std::ofstream m_log

Detailed Description

Definition at line 24 of file ConstraintApp.h.


Member Typedef Documentation

typedef boost::optional<KDL::Frame> ConstraintApp::OptionalKDLFrame

Definition at line 55 of file ConstraintApp.h.


Constructor & Destructor Documentation

Definition at line 8 of file ConstraintApp.cpp.

Definition at line 24 of file ConstraintApp.cpp.


Member Function Documentation

virtual void ConstraintApp::AffordanceFitHandler ( const drc::affordance_plus_t *  affordance) [pure virtual]

Implemented in ConstraintApp_MB.

virtual void ConstraintApp::AffordanceFitHandlerAux ( const lcm::ReceiveBuffer *  rbuf,
const std::string &  channel,
const drc::affordance_plus_t *  affordance 
) [inline, virtual]

Definition at line 47 of file ConstraintApp.h.

virtual void ConstraintApp::AffordanceTrackCollectionHandler ( const drc::affordance_track_collection_t *  affordance) [pure virtual]

Implemented in ConstraintApp_MB.

virtual void ConstraintApp::AffordanceTrackCollectionHandlerAux ( const lcm::ReceiveBuffer *  rbuf,
const std::string &  channel,
const drc::affordance_track_collection_t *  tracks 
) [inline, virtual]

Definition at line 41 of file ConstraintApp.h.

std::vector< double > ConstraintApp::FrameToVector ( const KDL::Frame &  frame) [static]

Definition at line 107 of file ConstraintApp.cpp.

virtual void ConstraintApp::GetCurrentStateEstimate ( std::vector< double > &  state) [pure virtual]

Implemented in ConstraintApp_MB.

virtual bool ConstraintApp::GetExpectedObservations ( const std::vector< double > &  state,
const std::vector< std::string > &  observationIds,
std::vector< double > &  observations 
) [pure virtual]

Implemented in ConstraintApp_MB.

ConstraintApp::OptionalKDLFrame ConstraintApp::GetFrameFromParams ( const drc::affordance_t *  msg) [static]

Definition at line 124 of file ConstraintApp.cpp.

virtual bool ConstraintApp::GetObservations ( std::vector< double > &  actualObservations,
std::vector< std::string > &  observationIds 
) [pure virtual]

Implemented in ConstraintApp_MB.

virtual bool ConstraintApp::GetResetAndClear ( ) [pure virtual]

Implemented in ConstraintApp_MB.

virtual int ConstraintApp::GetStateSize ( ) [pure virtual]

Implemented in ConstraintApp_MB.

int ConstraintApp::lcm_handle_timeout ( lcm_t *  lcm,
int  ms 
) [protected]

Definition at line 44 of file ConstraintApp.cpp.

void ConstraintApp::main ( ) [protected]

Definition at line 35 of file ConstraintApp.cpp.

virtual void ConstraintApp::SetCurrentStateEstimate ( const std::vector< double > &  state) [pure virtual]

Implemented in ConstraintApp_MB.

bool ConstraintApp::shouldStop ( ) [protected]

Definition at line 66 of file ConstraintApp.cpp.

void ConstraintApp::stopThreads ( ) [protected]

Definition at line 76 of file ConstraintApp.cpp.

KDL::Frame ConstraintApp::VectorToFrame ( const std::vector< double > &  state) [static]

Definition at line 86 of file ConstraintApp.cpp.

virtual bool ConstraintApp::WaitForObservations ( unsigned int  timeout_ms) [pure virtual]

Implemented in ConstraintApp_MB.


Member Data Documentation

lcm::LCM* ConstraintApp::m_lcm [protected]

Definition at line 72 of file ConstraintApp.h.

boost::mutex ConstraintApp::m_lcmMutex [protected]

Definition at line 71 of file ConstraintApp.h.

std::ofstream ConstraintApp::m_log [protected]

Definition at line 74 of file ConstraintApp.h.

boost::thread* ConstraintApp::m_mainThread [protected]

Definition at line 67 of file ConstraintApp.h.

volatile bool ConstraintApp::m_stopThreads [protected]

Definition at line 68 of file ConstraintApp.h.

boost::mutex ConstraintApp::m_stopThreadsMutex [protected]

Definition at line 69 of file ConstraintApp.h.


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs