void safety_set_allowed_area( uint8_t coordinate_frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) { mavlink_message_t msg; mavlink_msg_safety_set_allowed_area_pack_chan(UAS_PACK_CHAN(uas), &msg, UAS_PACK_TGT(uas), coordinate_frame, p1x, p1y, p1z, p2x, p2y, p2z); uas->mav_link->send_message(&msg); }
bool set_rate_cb(mavros::StreamRate::Request &req, mavros::StreamRate::Response &res) { mavlink_message_t msg; mavlink_msg_request_data_stream_pack_chan(UAS_PACK_CHAN(uas), &msg, UAS_PACK_TGT(uas), req.stream_id, req.message_rate, (req.on_off) ? 1 : 0 ); UAS_FCU(uas)->send_message(&msg); return true; }
//! message definiton here: @p https://pixhawk.ethz.ch/mavlink/#SET_ACTUATOR_CONTROL_TARGET void set_actuator_control_target(const uint64_t time_usec, const uint8_t group_mix, const float controls[8]) { mavlink_message_t msg; mavlink_msg_set_actuator_control_target_pack_chan(UAS_PACK_CHAN(uas), &msg, time_usec, group_mix, UAS_PACK_TGT(uas), controls); UAS_FCU(uas)->send_message(&msg); }
void set_attitude_target(uint32_t time_boot_ms, uint8_t type_mask, float q[4], float roll_rate, float pitch_rate, float yaw_rate, float thrust) { mavlink_message_t msg; mavlink_msg_set_attitude_target_pack_chan(UAS_PACK_CHAN(uas), &msg, time_boot_ms, UAS_PACK_TGT(uas), type_mask, q, roll_rate, pitch_rate, yaw_rate, thrust); uas->mav_link->send_message(&msg); }
void command_long(uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) { mavlink_message_t msg; mavlink_msg_command_long_pack_chan(UAS_PACK_CHAN(uas), &msg, UAS_PACK_TGT(uas), command, confirmation, param1, param2, param3, param4, param5, param6, param7); uas->mav_link->send_message(&msg); }