18 #include <condition_variable> 21 #include <mavros_msgs/CommandLong.h> 22 #include <mavros_msgs/CommandInt.h> 23 #include <mavros_msgs/CommandBool.h> 24 #include <mavros_msgs/CommandHome.h> 25 #include <mavros_msgs/CommandTOL.h> 26 #include <mavros_msgs/CommandTriggerControl.h> 27 #include <mavros_msgs/CommandTriggerInterval.h> 28 #include <mavros_msgs/CommandVtolTransition.h> 31 namespace std_plugins {
40 std::condition_variable
ack;
46 expected_command(command),
61 use_comp_id_system_control(false)
66 PluginBase::initialize(uas_);
68 double command_ack_timeout;
70 cmd_nh.param(
"command_ack_timeout", command_ack_timeout, ACK_TIMEOUT_DEFAULT);
71 cmd_nh.param(
"use_comp_id_system_control", use_comp_id_system_control,
false);
122 for (
auto &tr : ack_waiting_list) {
123 if (tr.expected_command == ack.command) {
124 tr.result = ack.result;
131 ack.command, ack.result);
138 if (tr.
ack.wait_for(lock, std::chrono::nanoseconds(command_ack_timeout_dt.
toNSec())) == std::cv_status::timeout) {
152 uint16_t command, uint8_t confirmation,
153 float param1,
float param2,
154 float param3,
float param4,
155 float param5,
float param6,
157 unsigned char &success, uint8_t &
result)
159 using mavlink::common::MAV_RESULT;
163 L_CommandTransaction::iterator ack_it;
166 for (
const auto &tr : ack_waiting_list) {
167 if (tr.expected_command == command) {
177 bool is_ack_required = (confirmation != 0 || m_uas->is_ardupilotmega() || m_uas->is_px4()) && !broadcast;
179 ack_it = ack_waiting_list.emplace(ack_waiting_list.end(), command);
181 command_long(broadcast,
182 command, confirmation,
188 if (is_ack_required) {
190 bool is_not_timeout = wait_ack_for(*ack_it);
193 success = is_not_timeout && ack_it->result ==
enum_value(MAV_RESULT::ACCEPTED);
194 result = ack_it->result;
196 ack_waiting_list.erase(ack_it);
210 uint8_t frame, uint16_t command,
211 uint8_t current, uint8_t autocontinue,
212 float param1,
float param2,
213 float param3,
float param4,
214 int32_t x, int32_t y,
216 unsigned char &success)
221 command_int(broadcast,
222 frame, command, current, autocontinue,
233 template<
typename MsgT>
236 using mavlink::minimal::MAV_COMPONENT;
238 const uint8_t tgt_sys_id = (broadcast) ? 0 : m_uas->get_tgt_system();
239 const uint8_t tgt_comp_id = (broadcast) ? 0 :
240 (use_comp_id_system_control) ?
241 enum_value(MAV_COMPONENT::COMP_ID_SYSTEM_CONTROL) : m_uas->get_tgt_component();
243 cmd.target_system = tgt_sys_id;
244 cmd.target_component = tgt_comp_id;
248 uint16_t command, uint8_t confirmation,
249 float param1,
float param2,
250 float param3,
float param4,
251 float param5,
float param6,
254 const uint8_t confirmation_fixed = (broadcast) ? 0 : confirmation;
256 mavlink::common::msg::COMMAND_LONG
cmd {};
257 set_target(
cmd, broadcast);
259 cmd.command = command;
260 cmd.confirmation = confirmation_fixed;
269 UAS_FCU(m_uas)->send_message_ignore_drop(
cmd);
273 uint8_t frame, uint16_t command,
274 uint8_t current, uint8_t autocontinue,
275 float param1,
float param2,
276 float param3,
float param4,
277 int32_t x, int32_t y,
280 mavlink::common::msg::COMMAND_INT
cmd {};
281 set_target(
cmd, broadcast);
284 cmd.command = command;
285 cmd.current = current;
286 cmd.autocontinue = autocontinue;
295 UAS_FCU(m_uas)->send_message_ignore_drop(
cmd);
301 mavros_msgs::CommandLong::Response &res)
303 return send_command_long_and_wait(req.broadcast,
304 req.command, req.confirmation,
305 req.param1, req.param2,
306 req.param3, req.param4,
307 req.param5, req.param6,
309 res.success, res.result);
313 mavros_msgs::CommandInt::Response &res)
315 return send_command_int(req.broadcast,
316 req.frame, req.command,
317 req.current, req.autocontinue,
318 req.param1, req.param2,
319 req.param3, req.param4,
325 mavros_msgs::CommandBool::Response &res)
327 using mavlink::common::MAV_CMD;
328 return send_command_long_and_wait(
false,
330 (req.value) ? 1.0 : 0.0,
332 res.success, res.result);
336 mavros_msgs::CommandHome::Response &res)
338 using mavlink::common::MAV_CMD;
339 return send_command_long_and_wait(
false,
341 (req.current_gps) ? 1.0 : 0.0,
342 0, 0, req.yaw, req.latitude, req.longitude, req.altitude,
343 res.success, res.result);
347 mavros_msgs::CommandTOL::Response &res)
349 using mavlink::common::MAV_CMD;
350 return send_command_long_and_wait(
false,
355 req.latitude, req.longitude, req.altitude,
356 res.success, res.result);
359 bool land_cb(mavros_msgs::CommandTOL::Request &req,
360 mavros_msgs::CommandTOL::Response &res)
362 using mavlink::common::MAV_CMD;
363 return send_command_long_and_wait(
false,
367 req.latitude, req.longitude, req.altitude,
368 res.success, res.result);
372 mavros_msgs::CommandTriggerControl::Response &res)
374 using mavlink::common::MAV_CMD;
375 return send_command_long_and_wait(
false,
377 (req.trigger_enable) ? 1.0 : 0.0,
378 (req.sequence_reset) ? 1.0 : 0.0,
379 (req.trigger_pause) ? 1.0 : 0.0,
381 res.success, res.result);
385 mavros_msgs::CommandTriggerInterval::Response &res)
387 using mavlink::common::MAV_CMD;
390 return send_command_long_and_wait(
false,
391 enum_value(MAV_CMD::DO_SET_CAM_TRIGG_INTERVAL), 1,
393 req.integration_time,
395 res.success, res.result);
399 mavros_msgs::CommandVtolTransition::Response &res)
401 using mavlink::common::MAV_CMD;
402 return send_command_long_and_wait(
false,
403 enum_value(MAV_CMD::DO_VTOL_TRANSITION),
false,
406 res.success, res.result);
MAVROS Plugin base class.
#define ROS_WARN_THROTTLE_NAMED(rate, name,...)
#define ROS_WARN_NAMED(name,...)
void set_target(MsgT &cmd, bool broadcast)
void initialize(UAS &uas_) override
Plugin initializer.
ros::ServiceServer trigger_interval_srv
ros::ServiceServer arming_srv
static constexpr double ACK_TIMEOUT_DEFAULT
std::lock_guard< std::mutex > lock_guard
void command_long(bool broadcast, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
bool trigger_control_cb(mavros_msgs::CommandTriggerControl::Request &req, mavros_msgs::CommandTriggerControl::Response &res)
std::list< CommandTransaction > L_CommandTransaction
bool command_long_cb(mavros_msgs::CommandLong::Request &req, mavros_msgs::CommandLong::Response &res)
ros::ServiceServer command_long_srv
ros::ServiceServer vtol_transition_srv
void handle_command_ack(const mavlink::mavlink_message_t *msg, mavlink::common::msg::COMMAND_ACK &ack)
ros::ServiceServer trigger_control_srv
uint16_t expected_command
bool arming_cb(mavros_msgs::CommandBool::Request &req, mavros_msgs::CommandBool::Response &res)
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
bool vtol_transition_cb(mavros_msgs::CommandVtolTransition::Request &req, mavros_msgs::CommandVtolTransition::Response &res)
bool send_command_long_and_wait(bool broadcast, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, unsigned char &success, uint8_t &result)
CommandTransaction(uint16_t command)
bool trigger_interval_cb(mavros_msgs::CommandTriggerInterval::Request &req, mavros_msgs::CommandTriggerInterval::Response &res)
bool set_home_cb(mavros_msgs::CommandHome::Request &req, mavros_msgs::CommandHome::Response &res)
bool takeoff_cb(mavros_msgs::CommandTOL::Request &req, mavros_msgs::CommandTOL::Response &res)
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
std::condition_variable ack
bool use_comp_id_system_control
L_CommandTransaction ack_waiting_list
bool send_command_int(bool broadcast, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z, unsigned char &success)
bool command_int_cb(mavros_msgs::CommandInt::Request &req, mavros_msgs::CommandInt::Response &res)
ros::ServiceServer command_int_srv
std::unique_lock< std::mutex > unique_lock
bool land_cb(mavros_msgs::CommandTOL::Request &req, mavros_msgs::CommandTOL::Response &res)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::ServiceServer takeoff_srv
ros::Duration command_ack_timeout_dt
bool wait_ack_for(CommandTransaction &tr)
ros::ServiceServer land_srv
void command_int(bool broadcast, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
ros::ServiceServer set_home_srv
constexpr std::underlying_type< _T >::type enum_value(_T e)
std::recursive_mutex mutex