Class UAS
Defined in File mavros_uas.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class UAS : public rclcpp::Node
UAS Node.
This class implements main translation mode. It loads plugins to support various sub-protocols.
Also each plugin can use that node to create sub-nodes or other RCLCPP objects.
UAS Node provides:
FCU messaging link
FCU System & Component ID pair
Connection status (mavplugin::SystemStatusPlugin)
Autopilot type (mavplugin::SystemStatusPlugin)
Vehicle type (mavplugin::SystemStatusPlugin)
Additional data trough mavros::uas::Data class
Public Functions
-
inline explicit UAS(const std::string &name_ = "mavros")
-
explicit UAS(const rclcpp::NodeOptions &options_ = rclcpp::NodeOptions(), const std::string &name_ = "mavros", const std::string &uas_url_ = "/uas1", uint8_t target_system_ = 1, uint8_t target_component_ = 1)
-
~UAS() = default
-
inline bool is_connected()
Return connection status.
-
void update_heartbeat(uint8_t type_, uint8_t autopilot_, uint8_t base_mode_)
Update autopilot type on every HEARTBEAT
-
void update_connection_status(bool conn_)
Update autopilot connection status (every HEARTBEAT/conn_timeout)
-
void add_connection_change_handler(ConnectionCb cb)
Add connection change handler callback.
-
inline MAV_AUTOPILOT get_autopilot()
Returns autopilot type.
-
inline bool get_armed()
Returns arming status.
Note
There may be race condition between SET_MODE and HEARTBEAT.
-
inline bool get_hil_state()
Returns HIL status.
-
inline uint8_t get_tgt_system()
Return communication target system.
-
inline uint8_t get_tgt_component()
Return communication target component.
-
inline void set_tgt(uint8_t sys, uint8_t comp)
-
void add_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr, std::vector<geometry_msgs::msg::TransformStamped> &vector)
Add static transform. To publish all static transforms at once, we stack them in a std::vector.
- Parameters:
frame_id – parent frame for transform
child_id – child frame for transform
tr – transform
vector – vector of transforms
-
void publish_static_transform(const std::string &frame_id, const std::string &child_id, const Eigen::Affine3d &tr)
Publishes static transform.
- Parameters:
frame_id – parent frame for transform
child_id – child frame for transform
tr – transform
-
inline void set_time_offset(uint64_t offset_ns)
-
inline uint64_t get_time_offset(void)
-
inline void set_timesync_mode(timesync_mode mode)
-
inline timesync_mode get_timesync_mode(void)
-
rclcpp::Time synchronise_stamp(uint32_t time_boot_ms)
Compute FCU message time from time_boot_ms or time_usec field.
Uses time_offset for calculation
- Returns:
FCU time if it is known else current wall time.
-
rclcpp::Time synchronise_stamp(uint64_t time_usec)
-
template<typename T>
inline std_msgs::msg::Header synchronized_header(const std::string &frame_id, const T time_stamp) Create message header from time_boot_ms or time_usec stamps and frame_id.
Setting frame_id and stamp are pretty common, this little helper should reduce LOC.
- Parameters:
frame_id – [in] frame for header
time_stamp – [in] mavlink message time
- Returns:
Header with syncronized stamp and frame id
-
uint64_t get_capabilities()
-
template<typename T>
inline bool has_capability(T capability) Function to check if the flight controller has a capability.
- Parameters:
capabilities – can accept a multiple capability params either in enum or int from
-
template<typename ...Ts>
inline bool has_capabilities(Ts... capabilities) Function to check if the flight controller has a set of capabilities.
- Parameters:
capabilities – can accept a multiple capability params either in enum or int from
-
void update_capabilities(bool known, uint64_t caps = 0)
Update the capabilities if they’ve changed every VERSION/timeout.
-
void add_capabilities_change_handler(CapabilitiesCb cb)
Adds a function to the capabilities callback queue.
- Parameters:
cb – A void function that takes a single mavlink::common::MAV_PROTOCOL_CAPABILITY(MAV_CAP) param
-
template<typename _T>
inline void msg_set_target(_T &msg) Helper template to set target id’s of message.
-
inline bool is_my_target(uint8_t sysid, uint8_t compid)
Check that sys/comp id’s is my target.
-
inline bool is_my_target(uint8_t sysid)
Check that system id is my target.
-
inline bool is_ardupilotmega()
Check that FCU is APM.
-
inline bool is_px4()
Check that FCU is PX4.
-
std::string str_mode_v10(uint8_t base_mode, uint32_t custom_mode)
Represent FCU mode as string.
Port pymavlink mavutil.mode_string_v10
Supported FCU’s:
APM:Plane
APM:Copter
PX4
- Parameters:
base_mode – [in] base mode
custom_mode – [in] custom mode data
-
bool cmode_from_str(std::string cmode_str, uint32_t &custom_mode)
Lookup custom mode for given string.
Complimentary to str_mode_v10()
- Parameters:
cmode_str – [in] string representation of mode
custom_mode – [out] decoded value
- Returns:
true if success
-
void send_message(const mavlink::Message &msg, const uint8_t src_compid)
Send message to UAS with custom component id.
-
void set_protocol_version(mavconn::Protocol ver)
sets protocol version