Go to the documentation of this file.
21 #include <mavros_msgs/CommandLong.h>
22 #include <mavros_msgs/MountControl.h>
23 #include <geometry_msgs/Quaternion.h>
24 #include <geometry_msgs/Vector3Stamped.h>
25 #include <mavros_msgs/MountConfigure.h>
28 namespace extra_plugins {
30 using mavlink::common::MAV_MOUNT_MODE;
31 using mavlink::common::MAV_CMD;
56 std::lock_guard<std::mutex> lock(
mutex);
61 std::lock_guard<std::mutex> lock(
mutex);
66 std::lock_guard<std::mutex> lock(
mutex);
74 std::lock_guard<std::mutex> lock(
mutex);
86 bool error_detected =
false;
89 if (
_mode != mavros_msgs::MountControl::MAV_MOUNT_MODE_MAVLINK_TARGETING) {
91 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Can not diagnose in this targeting mode");
98 std::lock_guard<std::mutex> lock(
mutex);
105 error_detected =
true;
108 error_detected =
true;
111 error_detected =
true;
131 stat.
summary(diagnostic_msgs::DiagnosticStatus::STALE,
"No MOUNT_ORIENTATION received in the last 5 s");
133 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"angle error too high");
135 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Normal");
138 stat.
addf(
"Roll err (deg)",
"%.1f", roll_err_deg);
139 stat.
addf(
"Pitch err (deg)",
"%.1f", pitch_err_deg);
140 stat.
addf(
"Yaw err (deg)",
"%.1f", yaw_err_deg);
200 double err_threshold_deg;
202 mount_nh.
param(
"err_threshold_deg", err_threshold_deg, 10.0);
204 ROS_WARN(
"Could not retrive debounce_s parameter value, using default (%f)", debounce_s);
207 ROS_WARN(
"Could not retrive err_threshold_deg parameter value, using default (%f)", err_threshold_deg);
251 mo.pitch = -mo.pitch;
255 mo.yaw_absolute = -mo.yaw_absolute;
258 geometry_msgs::Quaternion quaternion_msg;
271 void handle_mount_status(
const mavlink::mavlink_message_t *, mavlink::ardupilotmega::msg::MOUNT_STATUS &ms)
273 geometry_msgs::Vector3Stamped publish_msg;
277 publish_msg.header.frame_id =
std::to_string(ms.target_component);
279 auto vec = Eigen::Vector3d(ms.pointing_b, ms.pointing_a, ms.pointing_c) * M_PI / 18000.0;
286 geometry_msgs::Quaternion quaternion_msg;
299 mavlink::common::msg::COMMAND_LONG
cmd {};
304 cmd.param1 = req->pitch;
305 cmd.param2 = req->roll;
306 cmd.param3 = req->yaw;
307 cmd.param4 = req->altitude;
308 cmd.param5 = req->latitude;
309 cmd.param6 = req->longitude;
310 cmd.param7 = req->mode;
318 mavros_msgs::MountConfigure::Response &res)
320 using mavlink::common::MAV_CMD;
323 auto client =
nh.
serviceClient<mavros_msgs::CommandLong>(
"cmd/command");
325 mavros_msgs::CommandLong
cmd{};
327 cmd.request.broadcast =
false;
328 cmd.request.command =
enum_value(MAV_CMD::DO_MOUNT_CONFIGURE);
329 cmd.request.confirmation =
false;
330 cmd.request.param1 = req.mode;
331 cmd.request.param2 = req.stabilize_roll;
332 cmd.request.param3 = req.stabilize_pitch;
333 cmd.request.param4 = req.stabilize_yaw;
334 cmd.request.param5 = req.roll_input;
335 cmd.request.param6 = req.pitch_input;
336 cmd.request.param7 = req.yaw_input;
338 ROS_DEBUG_NAMED(
"mount",
"MountConfigure: Request mode %u ", req.mode);
340 res.success =
cmd.response.success;
346 ROS_ERROR_COND_NAMED(!res.success,
"mount",
"MountConfigure: command plugin service call failed!");
std::vector< HandlerInfo > Subscriptions
bool negate_measured_roll
float _setpoint_pitch_deg
bool getParam(const std::string &key, bool &b) const
#define UAS_FCU(uasobjptr)
ros::Publisher mount_orientation_pub
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
DiagnosticTask(const std::string name)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::recursive_mutex mutex
std::shared_ptr< MAVConnInterface const > ConstPtr
void command_cb(const mavros_msgs::MountControl::ConstPtr &req)
Send mount control commands to vehicle.
void handle_mount_orientation(const mavlink::mavlink_message_t *msg, mavlink::common::msg::MOUNT_ORIENTATION &mo)
Publish the mount orientation.
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
void set_debounce_s(double debounce_s)
#define ROS_ERROR_COND_NAMED(cond, name,...)
uint8_t get_tgt_component()
#define ROS_ERROR_NAMED(name,...)
ros::Subscriber command_sub
void set_status(float roll_deg, float pitch_deg, float yaw_deg, ros::Time timestamp)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void summary(const diagnostic_msgs::DiagnosticStatus &src)
void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_DEBUG_NAMED(name,...)
std::string to_string(ADSB_ALTITUDE_TYPE e)
#define UAS_DIAG(uasobjptr)
ros::Time _last_orientation_update
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
bool mount_configure_cb(mavros_msgs::MountConfigure::Request &req, mavros_msgs::MountConfigure::Response &res)
Subscriptions get_subscriptions() override
void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
virtual void initialize(UAS &uas)
MountStatusDiag(const std::string &name)
void initialize(UAS &uas_) override
void set_setpoint(float roll_deg, float pitch_deg, float yaw_deg, uint8_t mode)
void addf(const std::string &key, const char *format,...)
T param(const std::string ¶m_name, const T &default_val) const
ros::Publisher mount_status_pub
Eigen::Quaterniond quaternion_from_rpy(const double roll, const double pitch, const double yaw)
bool negate_measured_pitch
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
ros::ServiceServer configure_srv
MountStatusDiag mount_diag
constexpr std::underlying_type< _T >::type enum_value(_T e)
void set_err_threshold_deg(float threshold_deg)
void handle_mount_status(const mavlink::mavlink_message_t *, mavlink::ardupilotmega::msg::MOUNT_STATUS &ms)
Publish the mount status.
mavros_extras
Author(s): Vladimir Ermakov
, Amilcar Lucas
autogenerated on Tue May 6 2025 02:34:08