TelemetryConditions
Description
This module contains utility functions used as or to generate Condition functions. Conditions are functions used by MAVLinkMobilityBase to check if a MAVLink message is concluded and a new one should be sent to the simulator. They work by receiving incoming telemetry on their mavlink_message_t parameter and returning a boolean to flag if that telemetry completes the condition.
Functions
checkEmpty
bool checkEmpty(mavlink_message_t);
An empty condition
getCheckCmdAck
std::function<bool(mavlink_message_t)> getCheckCmdAck(uint8_t systemId, uint8_t componentId, unsigned short command, uint8_t senderSystemId);
Get a condition that waits for a specific command acknowledge message.
getCheckPreArm
std::function<bool(mavlink_message_t)> getCheckPreArm(uint8_t senderSystemId);
Get a condition that checks if the vehicles pre-arm is good
getCheckArm
std::function<bool(mavlink_message_t)> getCheckArm(uint8_t senderSystemId);
Get a condition that checks if the vehicle is armed
getCheckAltitude
std::function<bool(mavlink_message_t)> getCheckAltitude(int32_t altitude, int32_t tolerance, uint8_t senderSystemId);
Get a condition that checks if the vehicle has reached a specific altitude within a tolerance
getCheckMissionRequest
std::function<bool(mavlink_message_t)> getCheckMissionRequest(uint8_t systemid, uint8_t componentId, uint16_t sequenceNumber, uint8_t senderSystemId);
Get a condition that waits for a mission request message with a specific sequence number
getCheckMissionAck
std::function<bool(mavlink_message_t)> getCheckMissionAck(uint8_t systemId, uint8_t componentId, uint8_t senderSystemId);
Get a condition that waits for a mission ack message
getCheckMissionItemReached
std::function<bool(mavlink_message_t)> getCheckMissionItemReached(uint16_t seq, uint8_t senderSystemId);
Get a condition that waits for a mission item reached message
getCheckTargetGlobal
std::function<bool(mavlink_message_t)> getCheckTargetGlobal(float lat, float lon, float alt, uint8_t senderSystemId);
Get a condition that waits for a target global message with a specific location
getCheckGlobalPosition
std::function<bool(mavlink_message_t)> getCheckGlobalPosition(float lat, float lon, float alt, float tolerance, inet::IGeographicCoordinateSystem *coordinateSystem, uint8_t senderSystemId);
Get a condition that checks if the vehicle has reached a specific condition within tolerance
getCheckParamValue
std::function<bool(mavlink_message_t)> getCheckParamValue(std::string param_id, float param_value, uint8_t senderSystemId);
Get a condition that checks if a specific parameter has a desired value
getCheckMode
std::function<bool(mavlink_message_t)> getCheckMode(Mode mode, VehicleType type, uint8_t senderSystemId);
Get a condition that checks if the vehicle is on a specific mode