Classes | Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | Friends
Crazyflie Class Reference

#include <Crazyflie.h>

List of all members.

Classes

struct  batchRequest
struct  logInfo
struct  LogTocEntry
struct  MemoryTocEntry
struct  paramInfo
struct  ParamTocEntry
union  ParamValue
struct  poly4d

Public Types

enum  BootloaderTarget { TargetSTM32 = 0xFF, TargetNRF51 = 0xFE }
enum  LogType {
  LogTypeUint8 = 1, LogTypeUint16 = 2, LogTypeUint32 = 3, LogTypeInt8 = 4,
  LogTypeInt16 = 5, LogTypeInt32 = 6, LogTypeFloat = 7, LogTypeFP16 = 8
}
enum  MemoryType {
  MemoryTypeEEPROM = 0x00, MemoryTypeOneWire = 0x01, MemoryTypeLED12 = 0x10, MemoryTypeLOCO = 0x11,
  MemoryTypeTRAJ = 0x12
}
enum  ParamType {
  ParamTypeUint8 = 0x00 | (0x00<<2) | (0x01<<3), ParamTypeInt8 = 0x00 | (0x00<<2) | (0x00<<3), ParamTypeUint16 = 0x01 | (0x00<<2) | (0x01<<3), ParamTypeInt16 = 0x01 | (0x00<<2) | (0x00<<3),
  ParamTypeUint32 = 0x02 | (0x00<<2) | (0x01<<3), ParamTypeInt32 = 0x02 | (0x00<<2) | (0x00<<3), ParamTypeFloat = 0x02 | (0x01<<2) | (0x00<<3)
}

Public Member Functions

struct Crazyflie::poly4d __attribute__ ((packed))
template<class T >
void addSetParam (uint8_t id, const T &value)
void alloff ()
 Crazyflie (const std::string &link_uri, Logger &logger=EmptyLogger, std::function< void(const char *)> consoleCb=nullptr)
void emergencyStop ()
void emergencyStopWatchdog ()
std::string getDeviceTypeName ()
std::string getFirmwareVersion ()
template<class T >
getParam (uint8_t id) const
const ParamTocEntrygetParamTocEntry (const std::string &group, const std::string &name) const
int getProtocolVersion ()
void goTo (float x, float y, float z, float yaw, float duration, bool relative=false, uint8_t groupMask=0)
void land (float height, float duration, uint8_t groupMask=0)
void logReset ()
std::vector< LogTocEntry >
::const_iterator 
logVariablesBegin () const
std::vector< LogTocEntry >
::const_iterator 
logVariablesEnd () const
std::vector< MemoryTocEntry >
::const_iterator 
memoriesBegin () const
std::vector< MemoryTocEntry >
::const_iterator 
memoriesEnd () const
std::vector< ParamTocEntry >
::const_iterator 
paramsBegin () const
std::vector< ParamTocEntry >
::const_iterator 
paramsEnd () const
void queueOutgoingPacket (const crtpPacket_t &packet)
void readFlash (BootloaderTarget target, size_t size, std::vector< uint8_t > &data)
void reboot ()
void rebootFromBootloader ()
uint64_t rebootToBootloader ()
void requestLogToc (bool forceNoCache=false)
void requestMemoryToc ()
void requestParamToc (bool forceNoCache=false)
void sendExternalPoseUpdate (float x, float y, float z, float qx, float qy, float qz, float qw)
void sendExternalPositionUpdate (float x, float y, float z)
void sendFullStateSetpoint (float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, float qx, float qy, float qz, float qw, float rollRate, float pitchRate, float yawRate)
void sendHoverSetpoint (float vx, float vy, float yawrate, float zDistance)
void sendPing ()
void sendPositionSetpoint (float x, float y, float z, float yaw)
void sendSetpoint (float roll, float pitch, float yawrate, uint16_t thrust)
void sendStop ()
void setConsoleCallback (std::function< void(const char *)> cb)
void setEmptyAckCallback (std::function< void(const crtpPlatformRSSIAck *)> cb)
void setGenericPacketCallback (std::function< void(const ITransport::Ack &)> cb)
void setGroupMask (uint8_t groupMask)
void setLinkQualityCallback (std::function< void(float)> cb)
template<class T >
void setParam (uint8_t id, const T &value)
void setRequestedParams ()
void startSetParamRequest ()
void startTrajectory (uint8_t trajectoryId, float timescale=1.0, bool reversed=false, bool relative=true, uint8_t groupMask=0)
void stop (uint8_t groupMask=0)
void sysoff ()
void syson ()
void takeoff (float height, float duration, uint8_t groupMask=0)
void transmitPackets ()
void uploadTrajectory (uint8_t trajectoryId, uint32_t pieceOffset, const std::vector< poly4d > &pieces)
float vbat ()
void writeFlash (BootloaderTarget target, const std::vector< uint8_t > &data)

Static Public Member Functions

static size_t size (LogType t)

Private Member Functions

template<typename R >
void addRequest (const R &request, size_t numBytesToMatch)
void addRequestInternal (const uint8_t *data, size_t numBytes, size_t numBytesToMatch)
void addSetParam (uint8_t id, const ParamValue &value)
const LogTocEntrygetLogTocEntry (const std::string &group, const std::string &name) const
const ParamValuegetParam (uint8_t id) const
template<typename R >
const R * getRequestResult (size_t index) const
void handleAck (const ITransport::Ack &result)
void handleBatchAck (const ITransport::Ack &result, bool crtpMode)
void handleRequests (bool crtpMode=true, bool useSafeLink=ENABLE_SAFELINK, float baseTime=2.0, float timePerRequest=0.2)
uint8_t registerLogBlock (std::function< void(crtpLogDataResponse *, uint8_t)> cb)
template<typename R >
void sendPacket (const R &request, ITransport::Ack &result, bool useSafeLink=ENABLE_SAFELINK)
template<typename R >
void sendPacket (const R &request, bool useSafeLink=ENABLE_SAFELINK)
void sendPacketInternal (const uint8_t *data, uint32_t length, ITransport::Ack &result, bool useSafeLink=ENABLE_SAFELINK)
bool sendPacketInternal (const uint8_t *data, uint32_t length, bool useSafeLink=ENABLE_SAFELINK)
template<typename R >
void sendPacketOrTimeout (const R &request, bool useSafeLink=ENABLE_SAFELINK)
void sendPacketOrTimeoutInternal (const uint8_t *data, uint32_t length, bool useSafeLink=ENABLE_SAFELINK, float timeout=1.0)
void setParam (uint8_t id, const ParamValue &value)
void startBatchRequest ()
bool unregisterLogBlock (uint8_t id)

Private Attributes

struct Crazyflie::logInfo __attribute__
uint64_t m_address
std::vector< batchRequestm_batchRequests
uint8_t m_channel
std::function< void(const char *) m_consoleCallback )
int m_curr_down
int m_curr_up
Crazyradio::Datarate m_datarate
int m_devId
std::function< void(const
crtpPlatformRSSIAck *) 
m_emptyAckCallback )
std::function< void(const
ITransport::Ack &)> 
m_genericPacketCallback
std::function< void(float)> m_linkQualityCallback
bool m_log_use_V2
std::map< uint8_t,
std::function< void(crtpLogDataResponse
*, uint8_t)> 
m_logBlockCb )
Loggerm_logger
std::vector< LogTocEntrym_logTocEntries
std::vector< MemoryTocEntrym_memoryTocEntries
size_t m_numRequestsFinished
std::vector< crtpPacket_tm_outgoing_packets
bool m_param_use_V2
std::vector< ParamTocEntrym_paramTocEntries
std::map< uint8_t, ParamValuem_paramValues
int m_protocolVersion
Crazyradiom_radio
ITransportm_transport

Friends

class LogBlock
class LogBlockGeneric

Detailed Description

Definition at line 29 of file Crazyflie.h.


Member Enumeration Documentation

Enumerator:
TargetSTM32 
TargetNRF51 

Definition at line 83 of file Crazyflie.h.

Enumerator:
LogTypeUint8 
LogTypeUint16 
LogTypeUint32 
LogTypeInt8 
LogTypeInt16 
LogTypeInt32 
LogTypeFloat 
LogTypeFP16 

Definition at line 65 of file Crazyflie.h.

Enumerator:
MemoryTypeEEPROM 
MemoryTypeOneWire 
MemoryTypeLED12 
MemoryTypeLOCO 
MemoryTypeTRAJ 

Definition at line 88 of file Crazyflie.h.

Enumerator:
ParamTypeUint8 
ParamTypeInt8 
ParamTypeUint16 
ParamTypeInt16 
ParamTypeUint32 
ParamTypeInt32 
ParamTypeFloat 

Definition at line 32 of file Crazyflie.h.


Constructor & Destructor Documentation

Crazyflie::Crazyflie ( const std::string &  link_uri,
Logger logger = EmptyLogger,
std::function< void(const char *)>  consoleCb = nullptr 
)

Definition at line 32 of file Crazyflie.cpp.


Member Function Documentation

template<typename R >
void Crazyflie::addRequest ( const R &  request,
size_t  numBytesToMatch 
) [inline, private]

Definition at line 374 of file Crazyflie.h.

void Crazyflie::addRequestInternal ( const uint8_t *  data,
size_t  numBytes,
size_t  numBytesToMatch 
) [private]

Definition at line 1229 of file Crazyflie.cpp.

template<class T >
void Crazyflie::addSetParam ( uint8_t  id,
const T &  value 
) [inline]

Definition at line 220 of file Crazyflie.h.

void Crazyflie::addSetParam ( uint8_t  id,
const ParamValue value 
) [private]

Definition at line 880 of file Crazyflie.cpp.

Definition at line 331 of file Crazyflie.cpp.

Definition at line 185 of file Crazyflie.cpp.

Definition at line 191 of file Crazyflie.cpp.

Definition at line 152 of file Crazyflie.cpp.

Definition at line 143 of file Crazyflie.cpp.

const Crazyflie::LogTocEntry * Crazyflie::getLogTocEntry ( const std::string &  group,
const std::string &  name 
) const [private]

Definition at line 1179 of file Crazyflie.cpp.

template<class T >
T Crazyflie::getParam ( uint8_t  id) const [inline]

Definition at line 230 of file Crazyflie.h.

const ParamValue& Crazyflie::getParam ( uint8_t  id) const [inline, private]

Definition at line 451 of file Crazyflie.h.

const Crazyflie::ParamTocEntry * Crazyflie::getParamTocEntry ( const std::string &  group,
const std::string &  name 
) const

Definition at line 1191 of file Crazyflie.cpp.

Definition at line 134 of file Crazyflie.cpp.

template<typename R >
const R* Crazyflie::getRequestResult ( size_t  index) const [inline, private]

Definition at line 394 of file Crazyflie.h.

void Crazyflie::goTo ( float  x,
float  y,
float  z,
float  yaw,
float  duration,
bool  relative = false,
uint8_t  groupMask = 0 
)

Definition at line 1354 of file Crazyflie.cpp.

void Crazyflie::handleAck ( const ITransport::Ack result) [private]

Definition at line 1093 of file Crazyflie.cpp.

void Crazyflie::handleBatchAck ( const ITransport::Ack result,
bool  crtpMode 
) [private]

Definition at line 1297 of file Crazyflie.cpp.

void Crazyflie::handleRequests ( bool  crtpMode = true,
bool  useSafeLink = ENABLE_SAFELINK,
float  baseTime = 2.0,
float  timePerRequest = 0.2 
) [private]

Definition at line 1241 of file Crazyflie.cpp.

void Crazyflie::land ( float  height,
float  duration,
uint8_t  groupMask = 0 
)

Definition at line 1342 of file Crazyflie.cpp.

Definition at line 161 of file Crazyflie.cpp.

std::vector<LogTocEntry>::const_iterator Crazyflie::logVariablesBegin ( ) const [inline]

Definition at line 196 of file Crazyflie.h.

std::vector<LogTocEntry>::const_iterator Crazyflie::logVariablesEnd ( ) const [inline]

Definition at line 199 of file Crazyflie.h.

std::vector<MemoryTocEntry>::const_iterator Crazyflie::memoriesBegin ( ) const [inline]

Definition at line 203 of file Crazyflie.h.

std::vector<MemoryTocEntry>::const_iterator Crazyflie::memoriesEnd ( ) const [inline]

Definition at line 206 of file Crazyflie.h.

std::vector<ParamTocEntry>::const_iterator Crazyflie::paramsBegin ( ) const [inline]

Definition at line 189 of file Crazyflie.h.

std::vector<ParamTocEntry>::const_iterator Crazyflie::paramsEnd ( ) const [inline]

Definition at line 192 of file Crazyflie.h.

void Crazyflie::queueOutgoingPacket ( const crtpPacket_t packet) [inline]

En-queues a generic crtpPacket into a vector so that it can be transmitted later.

Parameters:
packetthe crtpPacket to be en-queued.

Definition at line 286 of file Crazyflie.h.

void Crazyflie::readFlash ( BootloaderTarget  target,
size_t  size,
std::vector< uint8_t > &  data 
)

Definition at line 508 of file Crazyflie.cpp.

Definition at line 273 of file Crazyflie.cpp.

Definition at line 315 of file Crazyflie.cpp.

Definition at line 284 of file Crazyflie.cpp.

uint8_t Crazyflie::registerLogBlock ( std::function< void(crtpLogDataResponse *, uint8_t)>  cb) [private]

Definition at line 1203 of file Crazyflie.cpp.

void Crazyflie::requestLogToc ( bool  forceNoCache = false)

Definition at line 572 of file Crazyflie.cpp.

Definition at line 843 of file Crazyflie.cpp.

void Crazyflie::requestParamToc ( bool  forceNoCache = false)

Definition at line 682 of file Crazyflie.cpp.

void Crazyflie::sendExternalPoseUpdate ( float  x,
float  y,
float  z,
float  qx,
float  qy,
float  qz,
float  qw 
)

Definition at line 242 of file Crazyflie.cpp.

void Crazyflie::sendExternalPositionUpdate ( float  x,
float  y,
float  z 
)

Definition at line 233 of file Crazyflie.cpp.

void Crazyflie::sendFullStateSetpoint ( float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz,
float  ax,
float  ay,
float  az,
float  qx,
float  qy,
float  qz,
float  qw,
float  rollRate,
float  pitchRate,
float  yawRate 
)

Definition at line 217 of file Crazyflie.cpp.

void Crazyflie::sendHoverSetpoint ( float  vx,
float  vy,
float  yawrate,
float  zDistance 
)

Definition at line 207 of file Crazyflie.cpp.

template<typename R >
void Crazyflie::sendPacket ( const R &  request,
ITransport::Ack result,
bool  useSafeLink = ENABLE_SAFELINK 
) [inline, private]

Definition at line 323 of file Crazyflie.h.

template<typename R >
void Crazyflie::sendPacket ( const R &  request,
bool  useSafeLink = ENABLE_SAFELINK 
) [inline, private]

Definition at line 338 of file Crazyflie.h.

void Crazyflie::sendPacketInternal ( const uint8_t *  data,
uint32_t  length,
ITransport::Ack result,
bool  useSafeLink = ENABLE_SAFELINK 
) [private]

Definition at line 1027 of file Crazyflie.cpp.

bool Crazyflie::sendPacketInternal ( const uint8_t *  data,
uint32_t  length,
bool  useSafeLink = ENABLE_SAFELINK 
) [private]

Definition at line 1001 of file Crazyflie.cpp.

template<typename R >
void Crazyflie::sendPacketOrTimeout ( const R &  request,
bool  useSafeLink = ENABLE_SAFELINK 
) [inline, private]

Definition at line 353 of file Crazyflie.h.

void Crazyflie::sendPacketOrTimeoutInternal ( const uint8_t *  data,
uint32_t  length,
bool  useSafeLink = ENABLE_SAFELINK,
float  timeout = 1.0 
) [private]

Definition at line 1011 of file Crazyflie.cpp.

Definition at line 250 of file Crazyflie.cpp.

void Crazyflie::sendPositionSetpoint ( float  x,
float  y,
float  z,
float  yaw 
)

Definition at line 197 of file Crazyflie.cpp.

void Crazyflie::sendSetpoint ( float  roll,
float  pitch,
float  yawrate,
uint16_t  thrust 
)

Definition at line 169 of file Crazyflie.cpp.

Definition at line 179 of file Crazyflie.cpp.

void Crazyflie::setConsoleCallback ( std::function< void(const char *)>  cb) [inline]

Definition at line 249 of file Crazyflie.h.

void Crazyflie::setEmptyAckCallback ( std::function< void(const crtpPlatformRSSIAck *)>  cb) [inline]

Definition at line 239 of file Crazyflie.h.

void Crazyflie::setGenericPacketCallback ( std::function< void(const ITransport::Ack &)>  cb) [inline]

Definition at line 277 of file Crazyflie.h.

void Crazyflie::setGroupMask ( uint8_t  groupMask)

Definition at line 1328 of file Crazyflie.cpp.

void Crazyflie::setLinkQualityCallback ( std::function< void(float)>  cb) [inline]

Definition at line 244 of file Crazyflie.h.

template<class T >
void Crazyflie::setParam ( uint8_t  id,
const T &  value 
) [inline]

Definition at line 211 of file Crazyflie.h.

void Crazyflie::setParam ( uint8_t  id,
const ParamValue value 
) [private]

Definition at line 994 of file Crazyflie.cpp.

Definition at line 989 of file Crazyflie.cpp.

static size_t Crazyflie::size ( LogType  t) [inline, static]

Definition at line 254 of file Crazyflie.h.

void Crazyflie::startBatchRequest ( ) [private]

Definition at line 1224 of file Crazyflie.cpp.

Definition at line 875 of file Crazyflie.cpp.

void Crazyflie::startTrajectory ( uint8_t  trajectoryId,
float  timescale = 1.0,
bool  reversed = false,
bool  relative = true,
uint8_t  groupMask = 0 
)

Definition at line 1392 of file Crazyflie.cpp.

void Crazyflie::stop ( uint8_t  groupMask = 0)

Definition at line 1348 of file Crazyflie.cpp.

Definition at line 323 of file Crazyflie.cpp.

void Crazyflie::syson ( )

Definition at line 339 of file Crazyflie.cpp.

void Crazyflie::takeoff ( float  height,
float  duration,
uint8_t  groupMask = 0 
)

Definition at line 1336 of file Crazyflie.cpp.

Transmits any outgoing packets to the crazyflie.

Definition at line 259 of file Crazyflie.cpp.

bool Crazyflie::unregisterLogBlock ( uint8_t  id) [private]

Definition at line 1215 of file Crazyflie.cpp.

void Crazyflie::uploadTrajectory ( uint8_t  trajectoryId,
uint32_t  pieceOffset,
const std::vector< poly4d > &  pieces 
)

Definition at line 1360 of file Crazyflie.cpp.

float Crazyflie::vbat ( )

Definition at line 347 of file Crazyflie.cpp.

void Crazyflie::writeFlash ( BootloaderTarget  target,
const std::vector< uint8_t > &  data 
)

Definition at line 360 of file Crazyflie.cpp.


Friends And Related Function Documentation

friend class LogBlock [friend]

Definition at line 478 of file Crazyflie.h.

friend class LogBlockGeneric [friend]

Definition at line 479 of file Crazyflie.h.


Member Data Documentation

uint64_t Crazyflie::m_address [private]

Definition at line 461 of file Crazyflie.h.

std::vector<batchRequest> Crazyflie::m_batchRequests [private]

Definition at line 489 of file Crazyflie.h.

uint8_t Crazyflie::m_channel [private]

Definition at line 460 of file Crazyflie.h.

std::function<void(const char*) Crazyflie::m_consoleCallback) [private]

Definition at line 474 of file Crazyflie.h.

int Crazyflie::m_curr_down [private]

Definition at line 493 of file Crazyflie.h.

int Crazyflie::m_curr_up [private]

Definition at line 492 of file Crazyflie.h.

Definition at line 462 of file Crazyflie.h.

int Crazyflie::m_devId [private]

Definition at line 458 of file Crazyflie.h.

std::function<void(const crtpPlatformRSSIAck*) Crazyflie::m_emptyAckCallback) [private]

Definition at line 472 of file Crazyflie.h.

std::function<void(const ITransport::Ack&)> Crazyflie::m_genericPacketCallback [private]

Definition at line 475 of file Crazyflie.h.

std::function<void(float)> Crazyflie::m_linkQualityCallback [private]

Definition at line 473 of file Crazyflie.h.

bool Crazyflie::m_log_use_V2 [private]

Definition at line 495 of file Crazyflie.h.

std::map<uint8_t, std::function<void(crtpLogDataResponse*, uint8_t)> Crazyflie::m_logBlockCb) [private]

Definition at line 465 of file Crazyflie.h.

Definition at line 501 of file Crazyflie.h.

std::vector<LogTocEntry> Crazyflie::m_logTocEntries [private]

Definition at line 464 of file Crazyflie.h.

Definition at line 470 of file Crazyflie.h.

Definition at line 490 of file Crazyflie.h.

Definition at line 364 of file Crazyflie.h.

bool Crazyflie::m_param_use_V2 [private]

Definition at line 496 of file Crazyflie.h.

Definition at line 467 of file Crazyflie.h.

std::map<uint8_t, ParamValue> Crazyflie::m_paramValues [private]

Definition at line 468 of file Crazyflie.h.

Definition at line 498 of file Crazyflie.h.

Definition at line 456 of file Crazyflie.h.

Definition at line 457 of file Crazyflie.h.


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


crazyflie_cpp
Author(s): Wolfgang Hoenig
autogenerated on Wed Jun 12 2019 19:20:44