Telemetry interface for the AscTec AutoPilot. More...
#include <telemetry.h>
Telemetry interface for the AscTec AutoPilot.
This class provides functions to help build request messages and it also provides a place for both the SerialInterface and the AutoPilot classes to pass telemetry information.
The most widely used methods are:
Definition at line 68 of file telemetry.h.
Constructor.
This handles telemetry packet storage and processing.
Definition at line 42 of file telemetry.cpp.
void asctec::Telemetry::buildRequest | ( | ) |
Enables Polling of a Request Message.
Due to the limited bandwidth available over the wireless link this function provides a means of selectivly enabling polling of various request messages. The interval argument allows for some messages to be polled more frequently than others, while the offset provides a way to space out the message requests.
msg | Message type to poll |
interval | Message Polling Interval (Message Hz = Polling HZ / interval) |
offset | (optional) Polling offset (interval = 2 & offset = 1 -> odd polling) |
Definition at line 74 of file telemetry.cpp.
Definition at line 448 of file telemetry.cpp.
Definition at line 489 of file telemetry.cpp.
void asctec::Telemetry::copyGPS_DATA | ( | ) |
Definition at line 456 of file telemetry.cpp.
Definition at line 471 of file telemetry.cpp.
void asctec::Telemetry::copyIMU_CALCDATA | ( | ) |
Definition at line 409 of file telemetry.cpp.
void asctec::Telemetry::copyIMU_RAWDATA | ( | ) |
Definition at line 394 of file telemetry.cpp.
void asctec::Telemetry::copyLL_STATUS | ( | ) |
Definition at line 381 of file telemetry.cpp.
void asctec::Telemetry::copyRC_DATA | ( | ) |
Definition at line 438 of file telemetry.cpp.
Definition at line 325 of file telemetry.cpp.
void asctec::Telemetry::dumpCTRL_INPUT | ( | ) |
Definition at line 370 of file telemetry.cpp.
void asctec::Telemetry::dumpGPS_DATA | ( | ) |
Definition at line 334 of file telemetry.cpp.
Definition at line 350 of file telemetry.cpp.
void asctec::Telemetry::dumpIMU_CALCDATA | ( | ) |
Definition at line 282 of file telemetry.cpp.
void asctec::Telemetry::dumpIMU_RAWDATA | ( | ) |
Definition at line 265 of file telemetry.cpp.
void asctec::Telemetry::dumpLL_STATUS | ( | ) |
Definition at line 248 of file telemetry.cpp.
void asctec::Telemetry::dumpRC_DATA | ( | ) |
Definition at line 313 of file telemetry.cpp.
void asctec::Telemetry::enableControl | ( | Telemetry * | telemetry_, |
uint8_t | interval = 1 , |
||
uint8_t | offset = 0 |
||
) |
Definition at line 180 of file telemetry.cpp.
void asctec::Telemetry::enablePolling | ( | RequestType | msg, |
uint8_t | interval = 1 , |
||
uint8_t | offset = 0 |
||
) |
Enables Polling of a Request Message.
Due to the limited bandwidth available over the wireless link this function provides a means of selectivly enabling polling of various request messages. The interval argument allows for some messages to be polled more frequently than others, while the offset provides a way to space out the message requests.
msg | Message type to poll |
interval | Message Polling Interval (Message Hz = Polling HZ / interval) |
offset | (optional) Polling offset (interval = 2 & offset = 1 -> odd polling) |
Definition at line 140 of file telemetry.cpp.
void asctec::Telemetry::estopCallback | ( | const std_msgs::Bool | msg | ) |
Definition at line 190 of file telemetry.cpp.
void asctec::Telemetry::publishPackets | ( | ) |
Definition at line 86 of file telemetry.cpp.
std::string asctec::Telemetry::requestToString | ( | RequestTypes::RequestType | t | ) |
Definition at line 204 of file telemetry.cpp.
uint16_t asctec::Telemetry::controlCount_ |
Definition at line 141 of file telemetry.h.
Definition at line 139 of file telemetry.h.
Definition at line 155 of file telemetry.h.
Definition at line 427 of file telemetry.h.
Definition at line 436 of file telemetry.h.
Definition at line 156 of file telemetry.h.
Definition at line 157 of file telemetry.h.
Definition at line 431 of file telemetry.h.
Definition at line 442 of file telemetry.h.
Definition at line 158 of file telemetry.h.
Definition at line 428 of file telemetry.h.
Definition at line 430 of file telemetry.h.
Definition at line 437 of file telemetry.h.
Definition at line 438 of file telemetry.h.
Definition at line 425 of file telemetry.h.
Definition at line 424 of file telemetry.h.
Definition at line 434 of file telemetry.h.
Definition at line 433 of file telemetry.h.
Definition at line 423 of file telemetry.h.
Definition at line 432 of file telemetry.h.
Definition at line 440 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CAMERACOMMANDS = 0x30 [static] |
Definition at line 187 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLCOMMANDS = 0x13 [static] |
Definition at line 169 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLFALCON = 0x18 [static] |
Definition at line 174 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLINPUT = 0x17 [static] |
Definition at line 173 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLINTERNAL = 0x14 [static] |
Definition at line 170 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLOUT = 0x11 [static] |
Definition at line 167 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLSTATUS = 0x16 [static] |
Definition at line 172 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CURRENTWAY = 0x21 [static] |
Definition at line 177 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_DEBUGDATA = 0x05 [static] |
Definition at line 165 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_FLIGHTPARAMS = 0x12 [static] |
Definition at line 168 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_GOTOCOMMAND = 0x25 [static] |
Definition at line 181 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_GPSDATA = 0x23 [static] |
Definition at line 179 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_GPSDATAADVANCED = 0x29 [static] |
Definition at line 185 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_HLSTATUS = 0x04 [static] |
Definition at line 164 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_HOMECOMMAND = 0x28 [static] |
Definition at line 184 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_IMUCALCDATA = 0x03 [static] |
Definition at line 163 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_IMURAWDATA = 0x01 [static] |
Definition at line 161 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_LANDCOMMAND = 0x27 [static] |
Definition at line 183 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_LAUNCHCOMMAND = 0x26 [static] |
Definition at line 182 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_LLSTATUS = 0x02 [static] |
Definition at line 162 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_NMEADATA = 0x22 [static] |
Definition at line 178 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_RCDATA = 0x15 [static] |
Definition at line 171 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_SINGLEWAYPOINT = 0x24 [static] |
Definition at line 180 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_WAYPOINT = 0x20 [static] |
Definition at line 176 of file telemetry.h.
Definition at line 138 of file telemetry.h.
Definition at line 426 of file telemetry.h.
Definition at line 435 of file telemetry.h.
Definition at line 149 of file telemetry.h.
const uint8_t asctec::Telemetry::REQUEST_TYPES = 9 [static] |
Definition at line 144 of file telemetry.h.
uint16_t asctec::Telemetry::requestCount_ |
Definition at line 140 of file telemetry.h.
Definition at line 150 of file telemetry.h.
Definition at line 151 of file telemetry.h.
std::bitset< 16 > asctec::Telemetry::requestPackets_ |
Definition at line 142 of file telemetry.h.
Definition at line 152 of file telemetry.h.
Definition at line 153 of file telemetry.h.
Definition at line 429 of file telemetry.h.