00001 #pragma once
00002
00003 #include <cstring>
00004 #include <sstream>
00005 #include <functional>
00006
00007 #include "Crazyradio.h"
00008 #include "crtp.h"
00009 #include <list>
00010 #include <set>
00011 #include <map>
00012 #include <chrono>
00013
00014 #define ENABLE_SAFELINK 1
00015
00016 class Logger
00017 {
00018 public:
00019 Logger() {}
00020 virtual ~Logger() {}
00021
00022 virtual void info(const std::string& ) {}
00023 virtual void warning(const std::string& ) {}
00024 virtual void error(const std::string& ) {}
00025 };
00026
00027 extern Logger EmptyLogger;
00028
00029 class Crazyflie
00030 {
00031 public:
00032 enum ParamType {
00033 ParamTypeUint8 = 0x00 | (0x00<<2) | (0x01<<3),
00034 ParamTypeInt8 = 0x00 | (0x00<<2) | (0x00<<3),
00035 ParamTypeUint16 = 0x01 | (0x00<<2) | (0x01<<3),
00036 ParamTypeInt16 = 0x01 | (0x00<<2) | (0x00<<3),
00037 ParamTypeUint32 = 0x02 | (0x00<<2) | (0x01<<3),
00038 ParamTypeInt32 = 0x02 | (0x00<<2) | (0x00<<3),
00039 ParamTypeFloat = 0x02 | (0x01<<2) | (0x00<<3),
00040 };
00041
00042 struct ParamTocEntry {
00043 uint16_t id;
00044 ParamType type;
00045 bool readonly;
00046
00047
00048
00049
00050
00051 std::string group;
00052 std::string name;
00053 };
00054
00055 union ParamValue{
00056 uint8_t valueUint8;
00057 int8_t valueInt8;
00058 uint16_t valueUint16;
00059 int16_t valueInt16;
00060 uint32_t valueUint32;
00061 int32_t valueInt32;
00062 float valueFloat;
00063 };
00064
00065 enum LogType {
00066 LogTypeUint8 = 1,
00067 LogTypeUint16 = 2,
00068 LogTypeUint32 = 3,
00069 LogTypeInt8 = 4,
00070 LogTypeInt16 = 5,
00071 LogTypeInt32 = 6,
00072 LogTypeFloat = 7,
00073 LogTypeFP16 = 8,
00074 };
00075
00076 struct LogTocEntry {
00077 uint8_t id;
00078 LogType type;
00079 std::string group;
00080 std::string name;
00081 };
00082
00083 enum BootloaderTarget {
00084 TargetSTM32 = 0xFF,
00085 TargetNRF51 = 0xFE,
00086 };
00087
00088 enum MemoryType {
00089 MemoryTypeEEPROM = 0x00,
00090 MemoryTypeOneWire = 0x01,
00091 MemoryTypeLED12 = 0x10,
00092 MemoryTypeLOCO = 0x11,
00093 MemoryTypeTRAJ = 0x12,
00094 };
00095
00096 struct MemoryTocEntry {
00097 uint16_t id;
00098 MemoryType type;
00099 uint32_t size;
00100 uint64_t addr;
00101 };
00102
00103 struct poly4d {
00104 float p[4][8];
00105 float duration;
00106 } __attribute__((packed));
00107
00108 public:
00109 Crazyflie(
00110 const std::string& link_uri,
00111 Logger& logger = EmptyLogger,
00112 std::function<void(const char*)> consoleCb = nullptr);
00113
00114 int getProtocolVersion();
00115
00116 std::string getFirmwareVersion();
00117
00118 std::string getDeviceTypeName();
00119
00120 void logReset();
00121
00122 void sendSetpoint(
00123 float roll,
00124 float pitch,
00125 float yawrate,
00126 uint16_t thrust);
00127
00128 void sendFullStateSetpoint(
00129 float x, float y, float z,
00130 float vx, float vy, float vz,
00131 float ax, float ay, float az,
00132 float qx, float qy, float qz, float qw,
00133 float rollRate, float pitchRate, float yawRate);
00134
00135 void sendHoverSetpoint(
00136 float vx,
00137 float vy,
00138 float yawrate,
00139 float zDistance);
00140
00141 void sendStop();
00142
00143 void emergencyStop();
00144
00145 void emergencyStopWatchdog();
00146
00147 void sendPositionSetpoint(
00148 float x,
00149 float y,
00150 float z,
00151 float yaw);
00152
00153 void sendExternalPositionUpdate(
00154 float x,
00155 float y,
00156 float z);
00157
00158 void sendExternalPoseUpdate(
00159 float x, float y, float z,
00160 float qx, float qy, float qz, float qw);
00161
00162 void sendPing();
00163
00164 void reboot();
00165
00166 uint64_t rebootToBootloader();
00167
00168 void rebootFromBootloader();
00169
00170 void sysoff();
00171 void alloff();
00172 void syson();
00173 float vbat();
00174
00175 void writeFlash(
00176 BootloaderTarget target,
00177 const std::vector<uint8_t>& data);
00178 void readFlash(
00179 BootloaderTarget target,
00180 size_t size,
00181 std::vector<uint8_t>& data);
00182
00183 void requestLogToc(bool forceNoCache=false);
00184
00185 void requestParamToc(bool forceNoCache=false);
00186
00187 void requestMemoryToc();
00188
00189 std::vector<ParamTocEntry>::const_iterator paramsBegin() const {
00190 return m_paramTocEntries.begin();
00191 }
00192 std::vector<ParamTocEntry>::const_iterator paramsEnd() const {
00193 return m_paramTocEntries.end();
00194 }
00195
00196 std::vector<LogTocEntry>::const_iterator logVariablesBegin() const {
00197 return m_logTocEntries.begin();
00198 }
00199 std::vector<LogTocEntry>::const_iterator logVariablesEnd() const {
00200 return m_logTocEntries.end();
00201 }
00202
00203 std::vector<MemoryTocEntry>::const_iterator memoriesBegin() const {
00204 return m_memoryTocEntries.begin();
00205 }
00206 std::vector<MemoryTocEntry>::const_iterator memoriesEnd() const {
00207 return m_memoryTocEntries.end();
00208 }
00209
00210 template<class T>
00211 void setParam(uint8_t id, const T& value) {
00212 ParamValue v;
00213 memcpy(&v, &value, sizeof(value));
00214 setParam(id, v);
00215 }
00216
00217 void startSetParamRequest();
00218
00219 template<class T>
00220 void addSetParam(uint8_t id, const T& value) {
00221 ParamValue v;
00222 memcpy(&v, &value, sizeof(value));
00223 addSetParam(id, v);
00224 }
00225
00226 void setRequestedParams();
00227
00228
00229 template<class T>
00230 T getParam(uint8_t id) const {
00231 ParamValue v = getParam(id);
00232 return *(reinterpret_cast<T*>(&v));
00233 }
00234
00235 const ParamTocEntry* getParamTocEntry(
00236 const std::string& group,
00237 const std::string& name) const;
00238
00239 void setEmptyAckCallback(
00240 std::function<void(const crtpPlatformRSSIAck*)> cb) {
00241 m_emptyAckCallback = cb;
00242 }
00243
00244 void setLinkQualityCallback(
00245 std::function<void(float)> cb) {
00246 m_linkQualityCallback = cb;
00247 }
00248
00249 void setConsoleCallback(
00250 std::function<void(const char*)> cb) {
00251 m_consoleCallback = cb;
00252 }
00253
00254 static size_t size(LogType t) {
00255 switch(t) {
00256 case LogTypeUint8:
00257 case LogTypeInt8:
00258 return 1;
00259 break;
00260 case LogTypeUint16:
00261 case LogTypeInt16:
00262 case LogTypeFP16:
00263 return 2;
00264 break;
00265 case LogTypeUint32:
00266 case LogTypeInt32:
00267 case LogTypeFloat:
00268 return 4;
00269 break;
00270 default:
00271
00272 return 0;
00273 }
00274 }
00275
00276
00277 void setGenericPacketCallback(
00278 std::function<void(const ITransport::Ack&)> cb) {
00279 m_genericPacketCallback = cb;
00280 }
00281
00286 void queueOutgoingPacket(const crtpPacket_t& packet) {
00287 m_outgoing_packets.push_back(packet);
00288 }
00289
00290 void transmitPackets();
00291
00292
00293 void setGroupMask(uint8_t groupMask);
00294
00295 void takeoff(float height, float duration, uint8_t groupMask = 0);
00296
00297 void land(float height, float duration, uint8_t groupMask = 0);
00298
00299 void stop(uint8_t groupMask = 0);
00300
00301 void goTo(float x, float y, float z, float yaw, float duration, bool relative = false, uint8_t groupMask = 0);
00302
00303 void uploadTrajectory(
00304 uint8_t trajectoryId,
00305 uint32_t pieceOffset,
00306 const std::vector<poly4d>& pieces);
00307
00308 void startTrajectory(
00309 uint8_t trajectoryId,
00310 float timescale = 1.0,
00311 bool reversed = false,
00312 bool relative = true,
00313 uint8_t groupMask = 0);
00314
00315 private:
00316 void sendPacketInternal(
00317 const uint8_t* data,
00318 uint32_t length,
00319 ITransport::Ack& result,
00320 bool useSafeLink = ENABLE_SAFELINK);
00321
00322 template<typename R>
00323 void sendPacket(
00324 const R& request,
00325 ITransport::Ack& result,
00326 bool useSafeLink = ENABLE_SAFELINK)
00327 {
00328 sendPacketInternal(
00329 reinterpret_cast<const uint8_t*>(&request), sizeof(request), result, useSafeLink);
00330 }
00331
00332 bool sendPacketInternal(
00333 const uint8_t* data,
00334 uint32_t length,
00335 bool useSafeLink = ENABLE_SAFELINK);
00336
00337 template<typename R>
00338 void sendPacket(
00339 const R& request,
00340 bool useSafeLink = ENABLE_SAFELINK)
00341 {
00342 sendPacketInternal(
00343 reinterpret_cast<const uint8_t*>(&request), sizeof(request), useSafeLink);
00344 }
00345
00346 void sendPacketOrTimeoutInternal(
00347 const uint8_t* data,
00348 uint32_t length,
00349 bool useSafeLink = ENABLE_SAFELINK,
00350 float timeout = 1.0);
00351
00352 template<typename R>
00353 void sendPacketOrTimeout(
00354 const R& request,
00355 bool useSafeLink = ENABLE_SAFELINK)
00356 {
00357 sendPacketOrTimeoutInternal(
00358 reinterpret_cast<const uint8_t*>(&request), sizeof(request), useSafeLink);
00359 }
00360
00361 void handleAck(
00362 const ITransport::Ack& result);
00363
00364 std::vector<crtpPacket_t> m_outgoing_packets;
00365
00366 void startBatchRequest();
00367
00368 void addRequestInternal(
00369 const uint8_t* data,
00370 size_t numBytes,
00371 size_t numBytesToMatch);
00372
00373 template<typename R>
00374 void addRequest(
00375 const R& request,
00376 size_t numBytesToMatch)
00377 {
00378 addRequestInternal(
00379 reinterpret_cast<const uint8_t*>(&request), sizeof(request), numBytesToMatch);
00380 }
00381
00382 void handleRequests(
00383 bool crtpMode = true,
00384 bool useSafeLink = ENABLE_SAFELINK,
00385 float baseTime = 2.0,
00386 float timePerRequest = 0.2);
00387
00388
00389 void handleBatchAck(
00390 const ITransport::Ack& result,
00391 bool crtpMode);
00392
00393 template<typename R>
00394 const R* getRequestResult(size_t index) const {
00395 return reinterpret_cast<const R*>(m_batchRequests[index].ack.data);
00396 }
00397
00398 private:
00399 struct logInfo {
00400 uint8_t len;
00401 uint32_t log_crc;
00402 uint8_t log_max_packet;
00403 uint8_t log_max_ops;
00404 };
00405
00407
00408 struct paramInfo {
00409 uint8_t len;
00410 uint32_t crc;
00411 };
00412
00413
00414
00415
00416
00417
00418
00419
00420
00421
00422
00423
00424
00425
00426
00427
00428
00429
00430
00431
00432
00433
00434
00435
00436 private:
00437 const LogTocEntry* getLogTocEntry(
00438 const std::string& group,
00439 const std::string& name) const;
00440
00441 uint8_t registerLogBlock(
00442 std::function<void(crtpLogDataResponse*, uint8_t)> cb);
00443
00444 bool unregisterLogBlock(
00445 uint8_t id);
00446
00447 void setParam(uint8_t id, const ParamValue& value);
00448 void addSetParam(uint8_t id, const ParamValue& value);
00449
00450
00451 const ParamValue& getParam(uint8_t id) const {
00452 return m_paramValues.at(id);
00453 }
00454
00455 private:
00456 Crazyradio* m_radio;
00457 ITransport* m_transport;
00458 int m_devId;
00459
00460 uint8_t m_channel;
00461 uint64_t m_address;
00462 Crazyradio::Datarate m_datarate;
00463
00464 std::vector<LogTocEntry> m_logTocEntries;
00465 std::map<uint8_t, std::function<void(crtpLogDataResponse*, uint8_t)> > m_logBlockCb;
00466
00467 std::vector<ParamTocEntry> m_paramTocEntries;
00468 std::map<uint8_t, ParamValue> m_paramValues;
00469
00470 std::vector<MemoryTocEntry> m_memoryTocEntries;
00471
00472 std::function<void(const crtpPlatformRSSIAck*)> m_emptyAckCallback;
00473 std::function<void(float)> m_linkQualityCallback;
00474 std::function<void(const char*)> m_consoleCallback;
00475 std::function<void(const ITransport::Ack&)> m_genericPacketCallback;
00476
00477 template<typename T>
00478 friend class LogBlock;
00479 friend class LogBlockGeneric;
00480
00481
00482 struct batchRequest
00483 {
00484 std::vector<uint8_t> request;
00485 size_t numBytesToMatch;
00486 ITransport::Ack ack;
00487 bool finished;
00488 };
00489 std::vector<batchRequest> m_batchRequests;
00490 size_t m_numRequestsFinished;
00491
00492 int m_curr_up;
00493 int m_curr_down;
00494
00495 bool m_log_use_V2;
00496 bool m_param_use_V2;
00497
00498 int m_protocolVersion;
00499
00500
00501 Logger& m_logger;
00502 };
00503
00504 template<class T>
00505 class LogBlock
00506 {
00507 public:
00508 LogBlock(
00509 Crazyflie* cf,
00510 std::list<std::pair<std::string, std::string> > variables,
00511 std::function<void(uint32_t, T*)>& callback)
00512 : m_cf(cf)
00513 , m_callback(callback)
00514 , m_id(0)
00515 {
00516 m_id = m_cf->registerLogBlock([=](crtpLogDataResponse* r, uint8_t s) { this->handleData(r, s);});
00517 if (m_cf->m_log_use_V2) {
00518 crtpLogCreateBlockV2Request request;
00519 request.id = m_id;
00520 int i = 0;
00521 for (auto&& pair : variables) {
00522 const Crazyflie::LogTocEntry* entry = m_cf->getLogTocEntry(pair.first, pair.second);
00523 if (entry) {
00524 request.items[i].logType = entry->type;
00525 request.items[i].id = entry->id;
00526 ++i;
00527 }
00528 else {
00529 std::stringstream sstr;
00530 sstr << "Could not find " << pair.first << "." << pair.second << " in log toc!";
00531 throw std::runtime_error(sstr.str());
00532 }
00533 }
00534
00535 m_cf->startBatchRequest();
00536 m_cf->addRequestInternal(reinterpret_cast<const uint8_t*>(&request), 3 + 3*i, 2);
00537 m_cf->handleRequests();
00538 auto r = m_cf->getRequestResult<crtpLogControlResponse>(0);
00539 if (r->result != crtpLogControlResultOk
00540 && r->result != crtpLogControlResultBlockExists) {
00541 std::stringstream sstr;
00542 sstr << "Could not create log block! Result: " << (int)r->result << " " << (int)m_id << " " << (int)r->requestByte1 << " " << (int)r->command;
00543 throw std::runtime_error(sstr.str());
00544 }
00545 } else {
00546 crtpLogCreateBlockRequest request;
00547 request.id = m_id;
00548 int i = 0;
00549 for (auto&& pair : variables) {
00550 const Crazyflie::LogTocEntry* entry = m_cf->getLogTocEntry(pair.first, pair.second);
00551 if (entry) {
00552 request.items[i].logType = entry->type;
00553 request.items[i].id = entry->id;
00554 ++i;
00555 }
00556 else {
00557 std::stringstream sstr;
00558 sstr << "Could not find " << pair.first << "." << pair.second << " in log toc!";
00559 throw std::runtime_error(sstr.str());
00560 }
00561 }
00562
00563 m_cf->startBatchRequest();
00564 m_cf->addRequestInternal(reinterpret_cast<const uint8_t*>(&request), 3 + 2*i, 2);
00565 m_cf->handleRequests();
00566 auto r = m_cf->getRequestResult<crtpLogControlResponse>(0);
00567 if (r->result != crtpLogControlResultOk
00568 && r->result != crtpLogControlResultBlockExists) {
00569 std::stringstream sstr;
00570 sstr << "Could not create log block! Result: " << (int)r->result << " " << (int)m_id << " " << (int)r->requestByte1 << " " << (int)r->command;
00571 throw std::runtime_error(sstr.str());
00572 }
00573 }
00574 }
00575
00576 ~LogBlock()
00577 {
00578 stop();
00579 m_cf->unregisterLogBlock(m_id);
00580 }
00581
00582
00583 void start(uint8_t period)
00584 {
00585 crtpLogStartRequest request(m_id, period);
00586 m_cf->startBatchRequest();
00587 m_cf->addRequest(request, 2);
00588 m_cf->handleRequests();
00589 }
00590
00591 void stop()
00592 {
00593 crtpLogStopRequest request(m_id);
00594 m_cf->startBatchRequest();
00595 m_cf->addRequest(request, 2);
00596 m_cf->handleRequests();
00597 }
00598
00599 private:
00600 void handleData(crtpLogDataResponse* response, uint8_t size) {
00601 if (size == sizeof(T)) {
00602 uint32_t time_in_ms = ((uint32_t)response->timestampHi << 8) | (response->timestampLo);
00603 T* t = (T*)response->data;
00604 m_callback(time_in_ms, t);
00605 }
00606 else {
00607 std::stringstream sstr;
00608 sstr << "Size doesn't match! Is: " << (size_t)size << " expected: " << sizeof(T);
00609 throw std::runtime_error(sstr.str());
00610 }
00611 }
00612
00613 private:
00614 Crazyflie* m_cf;
00615 std::function<void(uint32_t, T*)> m_callback;
00616 uint8_t m_id;
00617 };
00618
00620
00621 class LogBlockGeneric
00622 {
00623 public:
00624 LogBlockGeneric(
00625 Crazyflie* cf,
00626 const std::vector<std::string>& variables,
00627 void* userData,
00628 std::function<void(uint32_t, std::vector<double>*, void* userData)>& callback)
00629 : m_cf(cf)
00630 , m_userData(userData)
00631 , m_callback(callback)
00632 , m_id(0)
00633 {
00634 m_id = m_cf->registerLogBlock([=](crtpLogDataResponse* r, uint8_t s) { this->handleData(r, s);});
00635 if (m_cf->m_log_use_V2) {
00636 crtpLogCreateBlockV2Request request;
00637 request.id = m_id;
00638 int i = 0;
00639 size_t s = 0;
00640 for (auto&& var : variables) {
00641 auto pos = var.find(".");
00642 std::string first = var.substr(0, pos);
00643 std::string second = var.substr(pos+1);
00644 const Crazyflie::LogTocEntry* entry = m_cf->getLogTocEntry(first, second);
00645 if (entry) {
00646 s += Crazyflie::size(entry->type);
00647 if (s > 26) {
00648 std::stringstream sstr;
00649 sstr << "Can't configure that many variables in a single log block!"
00650 << " Ignoring " << first << "." << second << std::endl;
00651 throw std::runtime_error(sstr.str());
00652 } else {
00653 request.items[i].logType = entry->type;
00654 request.items[i].id = entry->id;
00655 ++i;
00656 m_types.push_back(entry->type);
00657 }
00658 }
00659 else {
00660 std::stringstream sstr;
00661 sstr << "Could not find " << first << "." << second << " in log toc!";
00662 throw std::runtime_error(sstr.str());
00663 }
00664 }
00665 m_cf->startBatchRequest();
00666 m_cf->addRequestInternal(reinterpret_cast<const uint8_t*>(&request), 3 + 3*i, 2);
00667 m_cf->handleRequests();
00668 auto r = m_cf->getRequestResult<crtpLogControlResponse>(0);
00669 if (r->result != crtpLogControlResultOk
00670 && r->result != crtpLogControlResultBlockExists) {
00671 throw std::runtime_error("Could not create log block!");
00672 }
00673 } else {
00674 crtpLogCreateBlockRequest request;
00675 request.id = m_id;
00676 int i = 0;
00677 size_t s = 0;
00678 for (auto&& var : variables) {
00679 auto pos = var.find(".");
00680 std::string first = var.substr(0, pos);
00681 std::string second = var.substr(pos+1);
00682 const Crazyflie::LogTocEntry* entry = m_cf->getLogTocEntry(first, second);
00683 if (entry) {
00684 s += Crazyflie::size(entry->type);
00685 if (s > 26) {
00686 std::stringstream sstr;
00687 sstr << "Can't configure that many variables in a single log block!"
00688 << " Ignoring " << first << "." << second << std::endl;
00689 throw std::runtime_error(sstr.str());
00690 } else {
00691 request.items[i].logType = entry->type;
00692 request.items[i].id = entry->id;
00693 ++i;
00694 m_types.push_back(entry->type);
00695 }
00696 }
00697 else {
00698 std::stringstream sstr;
00699 sstr << "Could not find " << first << "." << second << " in log toc!";
00700 throw std::runtime_error(sstr.str());
00701 }
00702 }
00703 m_cf->startBatchRequest();
00704 m_cf->addRequestInternal(reinterpret_cast<const uint8_t*>(&request), 3 + 2*i, 2);
00705 m_cf->handleRequests();
00706 auto r = m_cf->getRequestResult<crtpLogControlResponse>(0);
00707 if (r->result != crtpLogControlResultOk
00708 && r->result != crtpLogControlResultBlockExists) {
00709 throw std::runtime_error("Could not create log block!");
00710 }
00711 }
00712 }
00713
00714 ~LogBlockGeneric()
00715 {
00716 stop();
00717 m_cf->unregisterLogBlock(m_id);
00718 }
00719
00720
00721 void start(uint8_t period)
00722 {
00723 crtpLogStartRequest request(m_id, period);
00724 m_cf->startBatchRequest();
00725 m_cf->addRequest(request, 2);
00726 m_cf->handleRequests();
00727 }
00728
00729 void stop()
00730 {
00731 crtpLogStopRequest request(m_id);
00732 m_cf->startBatchRequest();
00733 m_cf->addRequest(request, 2);
00734 m_cf->handleRequests();
00735 }
00736
00737 private:
00738 void handleData(crtpLogDataResponse* response, uint8_t ) {
00739
00740 std::vector<double> result;
00741 size_t pos = 0;
00742 for (size_t i = 0; i < m_types.size(); ++i)
00743 {
00744 switch (m_types[i])
00745 {
00746 case Crazyflie::LogTypeUint8:
00747 {
00748 uint8_t value;
00749 memcpy(&value, &response->data[pos], sizeof(uint8_t));
00750 result.push_back(value);
00751 pos += sizeof(uint8_t);
00752 break;
00753 }
00754 case Crazyflie::LogTypeInt8:
00755 {
00756 int8_t value;
00757 memcpy(&value, &response->data[pos], sizeof(int8_t));
00758 result.push_back(value);
00759 pos += sizeof(int8_t);
00760 break;
00761 }
00762 case Crazyflie::LogTypeUint16:
00763 {
00764 uint16_t value;
00765 memcpy(&value, &response->data[pos], sizeof(uint16_t));
00766 result.push_back(value);
00767 pos += sizeof(uint16_t);
00768 break;
00769 }
00770 case Crazyflie::LogTypeInt16:
00771 {
00772 int16_t value;
00773 memcpy(&value, &response->data[pos], sizeof(int16_t));
00774 result.push_back(value);
00775 pos += sizeof(int16_t);
00776 break;
00777 }
00778 case Crazyflie::LogTypeUint32:
00779 {
00780 uint32_t value;
00781 memcpy(&value, &response->data[pos], sizeof(uint32_t));
00782 result.push_back(value);
00783 pos += sizeof(uint32_t);
00784 break;
00785 }
00786 case Crazyflie::LogTypeInt32:
00787 {
00788 int32_t value;
00789 memcpy(&value, &response->data[pos], sizeof(int32_t));
00790 result.push_back(value);
00791 pos += sizeof(int32_t);
00792 break;
00793 }
00794 case Crazyflie::LogTypeFloat:
00795 {
00796 float value;
00797 memcpy(&value, &response->data[pos], sizeof(float));
00798 result.push_back(value);
00799 pos += sizeof(float);
00800 break;
00801 }
00802 case Crazyflie::LogTypeFP16:
00803 {
00804 double value;
00805 memcpy(&value, &response->data[pos], sizeof(double));
00806 result.push_back(value);
00807 pos += sizeof(double);
00808 break;
00809 }
00810 }
00811 }
00812
00813 uint32_t time_in_ms = ((uint32_t)response->timestampHi << 8) | (response->timestampLo);
00814 m_callback(time_in_ms, &result, m_userData);
00815 }
00816
00817 private:
00818 Crazyflie* m_cf;
00819 void* m_userData;
00820 std::function<void(uint32_t, std::vector<double>*, void*)> m_callback;
00821 uint8_t m_id;
00822 std::vector<Crazyflie::LogType> m_types;
00823 };
00824
00826
00827 class CrazyflieBroadcaster
00828 {
00829 public:
00830 CrazyflieBroadcaster(
00831 const std::string& link_uri);
00832
00833
00834 void takeoff(float height, float duration, uint8_t groupMask = 0);
00835
00836 void land(float height, float duration, uint8_t groupMask = 0);
00837
00838 void stop(uint8_t groupMask = 0);
00839
00840
00841 void goTo(float x, float y, float z, float yaw, float duration, uint8_t groupMask = 0);
00842
00843
00844 void startTrajectory(
00845 uint8_t trajectoryId,
00846 float timescale = 1.0,
00847 bool reversed = false,
00848 uint8_t groupMask = 0);
00849
00850 struct externalPosition
00851 {
00852 uint8_t id;
00853 float x;
00854 float y;
00855 float z;
00856 };
00857
00858 void sendExternalPositions(
00859 const std::vector<externalPosition>& data);
00860
00861 struct externalPose
00862 {
00863 uint8_t id;
00864 float x;
00865 float y;
00866 float z;
00867 float qx;
00868 float qy;
00869 float qz;
00870 float qw;
00871 };
00872
00873
00874 void sendExternalPoses(
00875 const std::vector<externalPose>& data);
00876
00877 void emergencyStop();
00878
00879 void emergencyStopWatchdog();
00880
00881
00882
00883
00884
00885
00886
00887
00888
00889
00890
00891
00892
00893
00894 protected:
00895 void sendPacket(
00896 const uint8_t* data,
00897 uint32_t length);
00898
00899 void send2Packets(
00900 const uint8_t* data,
00901 uint32_t length);
00902
00903
00904
00905
00906
00907
00908
00909 private:
00910 Crazyradio* m_radio;
00911 int m_devId;
00912
00913 uint8_t m_channel;
00914 uint64_t m_address;
00915 Crazyradio::Datarate m_datarate;
00916 };