#include <mavHeartbeat.h>
Public Member Functions | |
void | activelySend () |
Implement the messages actively sending function. | |
MavHeartbeat (MavHandler &handler, std::string name, uint16_t gcsNum,...) | |
Constructor for Heartbeat Module. Recv buf size 4096. | |
void | passivelyReceive (mavlink_message_t &msg) |
Implement the messages passively handling function. | |
void | reactToHeartbeat (uint16_t gcsIdx, const mavlink_message_t *msg) |
React to heartbeat from specific GCS and execute hook. | |
bool | sendHeartbeatToAll () |
Send heartbeat to all GCS. | |
bool | sendHeartbeatToGcs (uint16_t gcsIdx) |
Send heartbeat to specific GCS. Compid is set to ALL. | |
void | setAutopilot (uint8_t mavAutopilot) |
Set autopilot. | |
void | setBaseMode (uint8_t mavMode) |
Set base mode. | |
void | setCustomMode (uint32_t customMode) |
Set custom mode. | |
void | setHeartbeatData (uint8_t mavType, uint8_t mavAutopilot, uint8_t mavMode, uint32_t customMode, uint8_t mavStatus, uint8_t mavVersion) |
Set the heartbeat package raw data. | |
void | setHeartbeatHook (void(*func)()) |
Set the responser function pointer for the heartbeat. | |
void | setMavlinkVersion (uint8_t mavVersion) |
Set mavlink version. | |
void | setSystemStatus (uint8_t mavStatus) |
Set status. | |
void | setType (uint8_t mavType) |
Set type. | |
~MavHeartbeat () | |
Private Attributes | |
mavlink_heartbeat_t | m_hbMsg |
void(* | m_hook )() |
mavlink_message_t | m_sendMsg |
Definition at line 23 of file mavHeartbeat.h.
dji2mav::MavHeartbeat::MavHeartbeat | ( | MavHandler & | handler, |
std::string | name, | ||
uint16_t | gcsNum, | ||
... | |||
) | [inline] |
Constructor for Heartbeat Module. Recv buf size 4096.
handler | : The reference of MavHandler Object |
name | : The name of this module |
gcsNum | : The number of GCS that the module employs |
... | : The indexes of GCS list, should be uint16_t |
Definition at line 32 of file mavHeartbeat.h.
dji2mav::MavHeartbeat::~MavHeartbeat | ( | ) | [inline] |
Definition at line 61 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::activelySend | ( | ) | [inline, virtual] |
Implement the messages actively sending function.
Implements dji2mav::MavModule.
Definition at line 216 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::passivelyReceive | ( | mavlink_message_t & | msg | ) | [inline, virtual] |
Implement the messages passively handling function.
msg | : The reference of received message |
Implements dji2mav::MavModule.
Definition at line 209 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::reactToHeartbeat | ( | uint16_t | gcsIdx, |
const mavlink_message_t * | msg | ||
) | [inline] |
React to heartbeat from specific GCS and execute hook.
gcsIdx | : Get the index of GCS |
msg | : Get the received message |
Definition at line 189 of file mavHeartbeat.h.
bool dji2mav::MavHeartbeat::sendHeartbeatToAll | ( | ) | [inline] |
Send heartbeat to all GCS.
Definition at line 169 of file mavHeartbeat.h.
bool dji2mav::MavHeartbeat::sendHeartbeatToGcs | ( | uint16_t | gcsIdx | ) | [inline] |
Send heartbeat to specific GCS. Compid is set to ALL.
gcsIdx | : The index of GCS |
Definition at line 150 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setAutopilot | ( | uint8_t | mavAutopilot | ) | [inline] |
Set autopilot.
mavAutopilot | : Default full supporting for everything |
Definition at line 104 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setBaseMode | ( | uint8_t | mavMode | ) | [inline] |
Set base mode.
mavMode | : Default autocontrol and disarmed |
Definition at line 113 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setCustomMode | ( | uint32_t | customMode | ) | [inline] |
Set custom mode.
customMode | : Default 0. Defined by user |
Definition at line 122 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setHeartbeatData | ( | uint8_t | mavType, |
uint8_t | mavAutopilot, | ||
uint8_t | mavMode, | ||
uint32_t | customMode, | ||
uint8_t | mavStatus, | ||
uint8_t | mavVersion | ||
) | [inline] |
Set the heartbeat package raw data.
mavType | : Default quadrotor type |
mavAutopilot | : Default full supporting for every |
mavMode | : Default autocontrol and disarmed |
customMode | : Default 0. Defined by user |
mavStatus | : Default vehicle grounded and standby |
mavVersion | : Default 3 |
Definition at line 76 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setHeartbeatHook | ( | void(*)() | func | ) | [inline] |
Set the responser function pointer for the heartbeat.
The | function pointer that is to be set |
Definition at line 200 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setMavlinkVersion | ( | uint8_t | mavVersion | ) | [inline] |
Set mavlink version.
mavVersion | : Default 3 |
Definition at line 140 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setSystemStatus | ( | uint8_t | mavStatus | ) | [inline] |
Set status.
mavStatus | : Default vehicle grounded and standby |
Definition at line 131 of file mavHeartbeat.h.
void dji2mav::MavHeartbeat::setType | ( | uint8_t | mavType | ) | [inline] |
Definition at line 224 of file mavHeartbeat.h.
void(* dji2mav::MavHeartbeat::m_hook)() [private] |
Definition at line 226 of file mavHeartbeat.h.
Definition at line 223 of file mavHeartbeat.h.