Go to the documentation of this file.
18 #include <condition_variable>
21 #include <mavros_msgs/ParamSet.h>
22 #include <mavros_msgs/ParamGet.h>
23 #include <mavros_msgs/ParamPull.h>
24 #include <mavros_msgs/ParamPush.h>
25 #include <mavros_msgs/Param.h>
28 namespace std_plugins {
51 using MT = mavlink::common::MAV_PARAM_TYPE;
60 void set_value(mavlink::common::msg::PARAM_VALUE &pmsg)
62 mavlink::mavlink_param_union_t uv;
63 uv.param_float = pmsg.param_value;
69 switch (pmsg.param_type) {
87 int_tmp = uv.param_int8;
91 int_tmp = uv.param_uint8;
95 int_tmp = uv.param_int16;
99 int_tmp = uv.param_uint16;
103 int_tmp = uv.param_int32;
107 int_tmp = uv.param_uint32;
111 float_tmp = uv.param_float;
117 ROS_WARN_NAMED(
"param",
"PM: Unsupported param %.16s (%u/%u) type: %u",
118 pmsg.param_id.data(), pmsg.param_index, pmsg.param_count, pmsg.param_type);
131 switch (pmsg.param_type) {
141 int_tmp = pmsg.param_value;
145 int_tmp = pmsg.param_value;
149 int_tmp = pmsg.param_value;
153 int_tmp = pmsg.param_value;
157 int_tmp = pmsg.param_value;
161 int_tmp = pmsg.param_value;
165 float_tmp = pmsg.param_value;
171 ROS_WARN_NAMED(
"param",
"PM: Unsupported param %.16s (%u/%u) type: %u",
172 pmsg.param_id.data(), pmsg.param_index, pmsg.param_count, pmsg.param_type);
183 mavlink::mavlink_param_union_t uv;
186 mavlink::set_string(ret.param_id,
param_id);
208 uv.param_int32 =
static_cast<int32_t
>(
param_value);
221 ret.param_value = uv.param_float;
230 mavlink::set_string(ret.param_id,
param_id);
241 ret.param_value =
static_cast<bool &
>(
param_value);
245 ret.param_value =
static_cast<int32_t &
>(
param_value);
249 ret.param_value =
static_cast<double &
>(
param_value);
298 mavros_msgs::Param
msg;
317 return param_id ==
"SYSID_SW_MREV" ||
352 std::condition_variable
ack;
375 PluginBase::initialize(uas_);
445 void handle_param_value(
const mavlink::mavlink_message_t *msg, mavlink::common::msg::PARAM_VALUE &pmsg)
455 auto &p = param_it->second;
458 p.set_value_apm_quirk(pmsg);
465 set_it->second->ack.notify_all();
471 ((p.param_index != pmsg.param_index &&
472 pmsg.param_index != UINT16_MAX) ||
473 p.param_count != pmsg.param_count),
475 "PR: Param " << p.to_string() <<
" different index: " << pmsg.param_index <<
"/" << pmsg.param_count);
482 p.param_index = pmsg.param_index;
483 p.param_count = pmsg.param_count;
486 p.set_value_apm_quirk(pmsg);
512 ROS_WARN_NAMED(
"param",
"PR: FCU does not know index for first element! "
513 "Param list may be truncated.");
524 if (it_is_first_requested) {
525 ROS_DEBUG_NAMED(
"param",
"PR: got a value of a requested param idx=%u, "
526 "resetting retries count", pmsg.param_index);
529 ROS_INFO_NAMED(
"param",
"PR: got an unsolicited param value idx=%u, "
540 "PR: parameters list received, but %zd parametars are missed",
546 ROS_DEBUG_NAMED(
"param",
"PR: requesting next timed out parameter idx=%u", first_miss_idx);
558 mavlink::common::msg::PARAM_REQUEST_LIST rql{};
568 ROS_DEBUG_NAMED(
"param",
"PR:m: request '%s', idx %d",
id.c_str(), index);
570 mavlink::common::msg::PARAM_REQUEST_READ rqr{};
572 rqr.param_index = index;
575 mavlink::set_string(rqr.param_id,
id);
586 auto ps = ([
this, &
param]() -> mavlink::common::msg::PARAM_SET {
588 return param.to_param_set_apm_qurk();
590 return param.to_param_set();
648 ROS_WARN_NAMED(
"param",
"PR: missing list is clear, but we in RXPARAM state, "
649 "maybe last rerequest fails. Params missed: %zd",
660 ROS_WARN_NAMED(
"param",
"PR: request param #%u timeout, retries left %zu, and %zu params still missing",
666 ROS_ERROR_NAMED(
"param",
"PR: request param #%u completely missing.", first_miss_idx);
673 ROS_WARN_NAMED(
"param",
"PR: %zu params still missing, trying to request next: #%u",
687 if (it->second->retries_remaining > 0) {
688 it->second->retries_remaining--;
689 ROS_WARN_NAMED(
"param",
"PR: Resend param set for %s, retries left %zu",
690 it->second->param.param_id.c_str(),
691 it->second->retries_remaining);
697 it->second->param.param_id.c_str());
698 it->second->is_timedout =
true;
699 it->second->ack.notify_all();
725 == std::cv_status::no_timeout
731 std::unique_lock<std::mutex> lock(opt->cond_mutex);
734 == std::cv_status::no_timeout
735 && !opt->is_timedout;
758 return is_not_timeout;
766 ROS_INFO_NAMED(
"param",
"PR: PX4 parameter _HASH_CHECK ignored: 0x%8x",
static_cast<int32_t
>(v));
780 bool pull_cb(mavros_msgs::ParamPull::Request &req,
781 mavros_msgs::ParamPull::Response &res)
828 bool push_cb(mavros_msgs::ParamPush::Request &req,
829 mavros_msgs::ParamPush::Response &res)
838 for (
auto &
param : param_dict) {
848 auto to_send = param_it->second;
851 to_send.param_value =
param.second;
866 res.param_transfered = tx_count;
875 bool set_cb(mavros_msgs::ParamSet::Request &req,
876 mavros_msgs::ParamSet::Response &res)
885 auto param_it =
parameters.find(req.param_id);
887 auto to_send = param_it->second;
890 if (req.value.integer != 0)
891 to_send.param_value =
static_cast<int>(req.value.integer);
892 else if (req.value.real != 0.0)
893 to_send.param_value = req.value.real;
894 else if (param_it->second.param_value.getType() == XmlRpc::XmlRpcValue::Type::TypeDouble)
895 to_send.param_value = req.value.real;
897 to_send.param_value = 0;
903 res.value.integer = param_it->second.to_integer();
904 res.value.real = param_it->second.to_real();
921 bool get_cb(mavros_msgs::ParamGet::Request &req,
922 mavros_msgs::ParamGet::Response &res)
926 auto param_it =
parameters.find(req.param_id);
930 res.value.integer = param_it->second.to_integer();
931 res.value.real = param_it->second.to_real();
Parameter set transaction data.
ros::ServiceServer pull_srv
std::condition_variable ack
std::string toXml() const
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
void setParam(const std::string &key, bool b) const
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
ros::Timer shedule_timer
for startup shedule fetch
std::string format(const std::string &fmt, Args ... args)
void restart_timeout_timer()
std::lock_guard< std::recursive_mutex > lock_guard
static constexpr int PARAM_TIMEOUT_MS
Param wait time.
void param_set(Parameter ¶m)
#define ROS_DEBUG_STREAM_NAMED(name, args)
PluginBase()
Plugin constructor Should not do anything before initialize()
bool getParam(const std::string &key, bool &b) const
#define UAS_FCU(uasobjptr)
helper accessor to FCU link interface
std::recursive_mutex mutex
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
bool is_ardupilotmega()
Check that FCU is APM.
bool set_cb(mavros_msgs::ParamSet::Request &req, mavros_msgs::ParamSet::Response &res)
sets parameter value @service ~param/set
static constexpr int LIST_TIMEOUT_MS
Receive all time.
#define ROS_ERROR_NAMED(name,...)
ParamSetOpt(Parameter &_p, size_t _rem)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
bool get_cb(mavros_msgs::ParamGet::Request &req, mavros_msgs::ParamGet::Response &res)
get parameter @service ~param/get
mavlink::common::MAV_PARAM_TYPE MT
bool wait_param_set_ack_for(std::shared_ptr< ParamSetOpt > opt)
void initialize(UAS &uas_) override
Plugin initializer.
bool send_param_set_and_wait(Parameter ¶m)
#define ROS_INFO_COND_NAMED(cond, name,...)
const ros::Duration LIST_TIMEOUT_DT
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_INFO_NAMED(name,...)
#define ROS_DEBUG_NAMED(name,...)
#define ROS_ERROR_STREAM_NAMED(name, args)
void setPeriod(const Duration &period, bool reset=true)
bool pull_cb(mavros_msgs::ParamPull::Request &req, mavros_msgs::ParamPull::Response &res)
fetches all parameters from device @service ~param/pull
void msg_set_target(_T &msg)
std::list< uint16_t > parameters_missing_idx
const ros::Duration PARAM_TIMEOUT_DT
mavlink::common::msg::PARAM_SET PARAM_SET
std::string to_string(timesync_mode e)
ros::Publisher param_value_pub
bool push_cb(mavros_msgs::ParamPush::Request &req, mavros_msgs::ParamPush::Response &res)
push all parameter value to device @service ~param/push
void set_value(mavlink::common::msg::PARAM_VALUE &pmsg)
ros::ServiceServer set_srv
bool rosparam_set_allowed(const Parameter &p)
Set ROS param only if name is good.
ros::ServiceServer get_srv
void timeout_cb(const ros::TimerEvent &event)
void handle_param_value(const mavlink::mavlink_message_t *msg, mavlink::common::msg::PARAM_VALUE &pmsg)
static bool check_exclude_param_id(std::string param_id)
std::unique_lock< std::recursive_mutex > unique_lock
Parameter manipulation plugin.
std::mutex list_cond_mutex
const Type & getType() const
#define ROS_WARN_STREAM_COND_NAMED(cond, name, args)
std::condition_variable list_receiving
#define ROS_WARN_STREAM_NAMED(name, args)
std::recursive_mutex mutex
bool is_px4()
Check that FCU is PX4.
void connection_cb(bool connected) override
const ros::Duration BOOTUP_TIME_DT
static constexpr int BOOTUP_TIME_MS
APM boot time.
mavros_msgs::Param to_msg()
void param_request_read(std::string id, int16_t index=-1)
MAVROS Plugin base class.
void param_request_list()
void shedule_pull(const ros::Duration &dt)
#define ROS_WARN_NAMED(name,...)
ros::Timer timeout_timer
for timeout resend
ros::ServiceServer push_srv
std::string to_string() const
PARAM_SET to_param_set()
Make PARAM_SET message. Set target ids manually!
T param(const std::string ¶m_name, const T &default_val)
static constexpr int _RETRIES_COUNT
void enable_connection_cb()
PARAM_SET to_param_set_apm_qurk()
Make PARAM_SET message. Set target ids manually!
HandlerInfo make_handler(const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
#define ROS_WARN_COND_NAMED(cond, name,...)
std::unordered_map< std::string, std::shared_ptr< ParamSetOpt > > set_parameters
std::unordered_map< std::string, Parameter > parameters
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
constexpr std::underlying_type< _T >::type enum_value(_T e)
void set_value_apm_quirk(mavlink::common::msg::PARAM_VALUE &pmsg)
void shedule_cb(const ros::TimerEvent &event)
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03