Telemetry interface for the AscTec AutoPilot. More...
#include <telemetry.h>
Classes | |
struct | CONTROLLER_OUTPUT |
struct | CTRL_INPUT |
struct | GPS_DATA |
struct | GPS_DATA_ADVANCED |
struct | IMU_CALCDATA |
struct | IMU_RAWDATA |
struct | LL_STATUS |
struct | RC_DATA |
struct | WAYPOINT |
Public Member Functions | |
void | buildRequest () |
Enables Polling of a Request Message. | |
void | copyCONTROLLER_OUTPUT () |
void | copyCTRL_INPUT (asctec_msgs::CtrlInput msg) |
void | copyGPS_DATA () |
void | copyGPS_DATA_ADVANCED () |
void | copyIMU_CALCDATA () |
void | copyIMU_RAWDATA () |
void | copyLL_STATUS () |
void | copyRC_DATA () |
void | dumpCONTROLLER_OUTPUT () |
void | dumpCTRL_INPUT () |
void | dumpGPS_DATA () |
void | dumpGPS_DATA_ADVANCED () |
void | dumpIMU_CALCDATA () |
void | dumpIMU_RAWDATA () |
void | dumpLL_STATUS () |
void | dumpRC_DATA () |
void | enableControl (Telemetry *telemetry_, uint8_t interval=1, uint8_t offset=0) |
void | enablePolling (RequestType msg, uint8_t interval=1, uint8_t offset=0) |
Enables Polling of a Request Message. | |
void | estopCallback (const std_msgs::Bool msg) |
void | publishPackets () |
std::string | requestToString (RequestTypes::RequestType t) |
Telemetry (ros::NodeHandle nh) | |
Constructor. | |
~Telemetry () | |
Destructor. | |
Public Attributes | |
uint16_t | controlCount_ |
bool | controlEnabled_ |
uint8_t | controlInterval_ |
struct CONTROLLER_OUTPUT | CONTROLLER_OUTPUT_ |
asctec_msgs::ControllerOutputPtr | ControllerOutput_ |
uint8_t | controlOffset_ |
ros::Subscriber | controlSubscriber_ |
struct CTRL_INPUT | CTRL_INPUT_ |
bool | estop_ |
ros::Subscriber | estopSubscriber_ |
struct GPS_DATA | GPS_DATA_ |
struct GPS_DATA_ADVANCED | GPS_DATA_ADVANCED_ |
asctec_msgs::GPSDataPtr | GPSData_ |
asctec_msgs::GPSDataAdvancedPtr | GPSDataAdvanced_ |
struct IMU_CALCDATA | IMU_CALCDATA_ |
struct IMU_RAWDATA | IMU_RAWDATA_ |
asctec_msgs::IMUCalcDataPtr | IMUCalcData_ |
asctec_msgs::IMURawDataPtr | IMURawData_ |
struct LL_STATUS | LL_STATUS_ |
asctec_msgs::LLStatusPtr | LLStatus_ |
ros::NodeHandle | nh_ |
bool | pollingEnabled_ |
struct RC_DATA | RC_DATA_ |
asctec_msgs::RCDataPtr | RCData_ |
uint16_t | REQUEST_BITMASK [REQUEST_TYPES] |
uint16_t | requestCount_ |
uint8_t | requestInterval_ [REQUEST_TYPES] |
uint8_t | requestOffset_ [REQUEST_TYPES] |
std::bitset< 16 > | requestPackets_ |
ros::Publisher | requestPublisher_ [REQUEST_TYPES] |
ros::Time | timestamps_ [REQUEST_TYPES] |
struct WAYPOINT | WAYPOINT_ |
Static Public Attributes | |
static const uint8_t | PD_CAMERACOMMANDS = 0x30 |
static const uint8_t | PD_CTRLCOMMANDS = 0x13 |
static const uint8_t | PD_CTRLFALCON = 0x18 |
static const uint8_t | PD_CTRLINPUT = 0x17 |
static const uint8_t | PD_CTRLINTERNAL = 0x14 |
static const uint8_t | PD_CTRLOUT = 0x11 |
static const uint8_t | PD_CTRLSTATUS = 0x16 |
static const uint8_t | PD_CURRENTWAY = 0x21 |
static const uint8_t | PD_DEBUGDATA = 0x05 |
static const uint8_t | PD_FLIGHTPARAMS = 0x12 |
static const uint8_t | PD_GOTOCOMMAND = 0x25 |
static const uint8_t | PD_GPSDATA = 0x23 |
static const uint8_t | PD_GPSDATAADVANCED = 0x29 |
static const uint8_t | PD_HLSTATUS = 0x04 |
static const uint8_t | PD_HOMECOMMAND = 0x28 |
static const uint8_t | PD_IMUCALCDATA = 0x03 |
static const uint8_t | PD_IMURAWDATA = 0x01 |
static const uint8_t | PD_LANDCOMMAND = 0x27 |
static const uint8_t | PD_LAUNCHCOMMAND = 0x26 |
static const uint8_t | PD_LLSTATUS = 0x02 |
static const uint8_t | PD_NMEADATA = 0x22 |
static const uint8_t | PD_RCDATA = 0x15 |
static const uint8_t | PD_SINGLEWAYPOINT = 0x24 |
static const uint8_t | PD_WAYPOINT = 0x20 |
static const uint8_t | REQUEST_TYPES = 9 |
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 66 of file telemetry.h.
asctec::Telemetry::Telemetry | ( | ros::NodeHandle | nh | ) |
Constructor.
This handles telemetry packet storage and processing.
Definition at line 42 of file telemetry.cpp.
asctec::Telemetry::~Telemetry | ( | ) |
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.
void asctec::Telemetry::copyCONTROLLER_OUTPUT | ( | ) |
Definition at line 448 of file telemetry.cpp.
void asctec::Telemetry::copyCTRL_INPUT | ( | asctec_msgs::CtrlInput | msg | ) |
Definition at line 489 of file telemetry.cpp.
void asctec::Telemetry::copyGPS_DATA | ( | ) |
Definition at line 456 of file telemetry.cpp.
void asctec::Telemetry::copyGPS_DATA_ADVANCED | ( | ) |
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.
void asctec::Telemetry::dumpCONTROLLER_OUTPUT | ( | ) |
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.
void asctec::Telemetry::dumpGPS_DATA_ADVANCED | ( | ) |
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 139 of file telemetry.h.
Definition at line 137 of file telemetry.h.
Definition at line 153 of file telemetry.h.
Definition at line 425 of file telemetry.h.
asctec_msgs::ControllerOutputPtr asctec::Telemetry::ControllerOutput_ |
Definition at line 434 of file telemetry.h.
Definition at line 154 of file telemetry.h.
ros::Subscriber asctec::Telemetry::controlSubscriber_ |
Definition at line 155 of file telemetry.h.
Definition at line 429 of file telemetry.h.
Definition at line 440 of file telemetry.h.
ros::Subscriber asctec::Telemetry::estopSubscriber_ |
Definition at line 156 of file telemetry.h.
Definition at line 426 of file telemetry.h.
Definition at line 428 of file telemetry.h.
asctec_msgs::GPSDataPtr asctec::Telemetry::GPSData_ |
Definition at line 435 of file telemetry.h.
asctec_msgs::GPSDataAdvancedPtr asctec::Telemetry::GPSDataAdvanced_ |
Definition at line 436 of file telemetry.h.
Definition at line 423 of file telemetry.h.
Definition at line 422 of file telemetry.h.
asctec_msgs::IMUCalcDataPtr asctec::Telemetry::IMUCalcData_ |
Definition at line 432 of file telemetry.h.
asctec_msgs::IMURawDataPtr asctec::Telemetry::IMURawData_ |
Definition at line 431 of file telemetry.h.
Definition at line 421 of file telemetry.h.
asctec_msgs::LLStatusPtr asctec::Telemetry::LLStatus_ |
Definition at line 430 of file telemetry.h.
ros::NodeHandle asctec::Telemetry::nh_ |
Definition at line 438 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CAMERACOMMANDS = 0x30 [static] |
Definition at line 185 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLCOMMANDS = 0x13 [static] |
Definition at line 167 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLFALCON = 0x18 [static] |
Definition at line 172 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLINPUT = 0x17 [static] |
Definition at line 171 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLINTERNAL = 0x14 [static] |
Definition at line 168 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLOUT = 0x11 [static] |
Definition at line 165 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CTRLSTATUS = 0x16 [static] |
Definition at line 170 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_CURRENTWAY = 0x21 [static] |
Definition at line 175 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_DEBUGDATA = 0x05 [static] |
Definition at line 163 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_FLIGHTPARAMS = 0x12 [static] |
Definition at line 166 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_GOTOCOMMAND = 0x25 [static] |
Definition at line 179 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_GPSDATA = 0x23 [static] |
Definition at line 177 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_GPSDATAADVANCED = 0x29 [static] |
Definition at line 183 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_HLSTATUS = 0x04 [static] |
Definition at line 162 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_HOMECOMMAND = 0x28 [static] |
Definition at line 182 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_IMUCALCDATA = 0x03 [static] |
Definition at line 161 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_IMURAWDATA = 0x01 [static] |
Definition at line 159 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_LANDCOMMAND = 0x27 [static] |
Definition at line 181 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_LAUNCHCOMMAND = 0x26 [static] |
Definition at line 180 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_LLSTATUS = 0x02 [static] |
Definition at line 160 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_NMEADATA = 0x22 [static] |
Definition at line 176 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_RCDATA = 0x15 [static] |
Definition at line 169 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_SINGLEWAYPOINT = 0x24 [static] |
Definition at line 178 of file telemetry.h.
const uint8_t asctec::Telemetry::PD_WAYPOINT = 0x20 [static] |
Definition at line 174 of file telemetry.h.
Definition at line 136 of file telemetry.h.
Definition at line 424 of file telemetry.h.
asctec_msgs::RCDataPtr asctec::Telemetry::RCData_ |
Definition at line 433 of file telemetry.h.
Definition at line 147 of file telemetry.h.
const uint8_t asctec::Telemetry::REQUEST_TYPES = 9 [static] |
Definition at line 142 of file telemetry.h.
uint16_t asctec::Telemetry::requestCount_ |
Definition at line 138 of file telemetry.h.
Definition at line 148 of file telemetry.h.
Definition at line 149 of file telemetry.h.
std::bitset< 16 > asctec::Telemetry::requestPackets_ |
Definition at line 140 of file telemetry.h.
ros::Publisher asctec::Telemetry::requestPublisher_[REQUEST_TYPES] |
Definition at line 150 of file telemetry.h.
ros::Time asctec::Telemetry::timestamps_[REQUEST_TYPES] |
Definition at line 151 of file telemetry.h.
Definition at line 427 of file telemetry.h.