26 #define MAX_OBS_FEATURES 100
37 Feature(GeometricEntityKinds entity_kind);
40 double dimension()
const;
41 double codimension()
const;
44 const MatrixXd& Cov()
const;
45 double Cov(
int i,
int j)
const;
46 void SetCov(
const MatrixXd& c) { uloc_.SetCov(c); };
48 const Uloc& uloc(
void)
const {
return uloc_; };
49 void set_uloc(
const Uloc& u) { uloc_ = u; };
51 void ComputeSegmentLength(
Uloc p1,
Uloc p2);
53 void SetScan(
const GuiSplit &split) { split_ = split; };
55 const GuiSplit &GetScan(
void)
const {
return split_; };
57 void GeometricRelationsObservationPointToPoint(
Uloc Lsp1,
Uloc Lsp2);
73 void AddObservedFeature(
Feature f);
76 const Feature & features(
int f)
const;
78 void Clear(
void) { features_.clear(); }
81 vector<Feature> features_;
82 vector<bool> is_paired_;
Definition: feature.hh:34
static bool MatchMessage(player_msghdr_t *hdr, int type, int subtype, player_devaddr_t addr)
Helper for message processing.
Definition: message.h:159
Generic message header.
Definition: player.h:162
unsigned int GetDataSize()
Size of message data.
Definition: message.h:190
virtual int MainSetup(void)
Sets up the resources needed by the driver thread.
Definition: driver.h:658
virtual void MainQuit(void)
Cleanup method for driver thread (called when main exits)
Definition: driver.h:664
uint8_t type
Message type; must be one of PLAYER_MSGTYPE_*.
Definition: player.h:166
Encapsulates a device (i.e., a driver bound to an interface)
Definition: device.h:75
const char * ReadString(int section, const char *name, const char *value)
Read a string value.
virtual void Main(void)=0
Main method for driver thread.
void * GetPayload()
Get pointer to payload.
Definition: message.h:188
#define PLAYER_MSGTYPE_DATA
A data message.
Definition: player.h:95
#define PLAYER_MSGTYPE_RESP_ACK
A positive response message.
Definition: player.h:112
virtual int ProcessMessage(QueuePointer &resp_queue, player_msghdr *hdr, void *data)
Message handler.
Definition: feature.hh:68
#define PLAYER_MSGTYPE_REQ
A request message.
Definition: player.h:106
Integer property class.
Definition: property.h:115
int ReadDeviceAddr(player_devaddr_t *addr, int section, const char *name, int code, int index, const char *key)
Read a device id.
Class for loading configuration file information.
Definition: configfile.h:197
#define PLAYER_CAPABILITIES_REQ
Capability request message type.
Definition: player.h:397
A device address.
Definition: player.h:146
An autopointer for the message queue.
Definition: message.h:74
Feature(GeometricEntityKinds entity_kind)
Defaults to EDGE.
Definition: feature.cc:27
#define PLAYER_ERROR(msg)
Definition: error.h:81
Base class for drivers which oeprate with a thread.
Definition: driver.h:553
double timestamp
Time associated with message contents (seconds since epoch)
Definition: player.h:170
Reference-counted message objects.
Definition: message.h:133
Base class for all drivers.
Definition: driver.h:109
player_msghdr_t * GetHeader()
Get pointer to header.
Definition: message.h:186
#define PLAYER_MSGQUEUE_DEFAULT_MAXLEN
Default maximum length for a message queue.
Definition: player.h:76