Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
mavros::std_plugins::ParamPlugin Class Reference

Parameter manipulation plugin. More...

Inheritance diagram for mavros::std_plugins::ParamPlugin:
Inheritance graph
[legend]

Public Member Functions

Subscriptions get_subscriptions ()
 Return vector of MAVLink message subscriptions (handlers) More...
 
void initialize (UAS &uas_)
 Plugin initializer. More...
 
 ParamPlugin ()
 
- Public Member Functions inherited from mavros::plugin::PluginBase
virtual ~PluginBase ()
 

Private Types

using lock_guard = std::lock_guard< std::recursive_mutex >
 
enum  PR {
  PR::IDLE, PR::RXLIST, PR::RXPARAM, PR::RXPARAM_TIMEDOUT,
  PR::TXPARAM
}
 
using unique_lock = std::unique_lock< std::recursive_mutex >
 

Private Member Functions

void connection_cb (bool connected) override
 
bool get_cb (mavros_msgs::ParamGet::Request &req, mavros_msgs::ParamGet::Response &res)
 get parameter ~param/get More...
 
void go_idle ()
 
void handle_param_value (const mavlink::mavlink_message_t *msg, mavlink::common::msg::PARAM_VALUE &pmsg)
 
void param_request_list ()
 
void param_request_read (std::string id, int16_t index=-1)
 
void param_set (Parameter &param)
 
bool pull_cb (mavros_msgs::ParamPull::Request &req, mavros_msgs::ParamPull::Response &res)
 fetches all parameters from device ~param/pull More...
 
bool push_cb (mavros_msgs::ParamPush::Request &req, mavros_msgs::ParamPush::Response &res)
 push all parameter value to device ~param/push More...
 
void restart_timeout_timer ()
 
bool rosparam_set_allowed (const Parameter &p)
 Set ROS param only if name is good. More...
 
bool send_param_set_and_wait (Parameter &param)
 
bool set_cb (mavros_msgs::ParamSet::Request &req, mavros_msgs::ParamSet::Response &res)
 sets parameter value ~param/set More...
 
void shedule_cb (const ros::TimerEvent &event)
 
void shedule_pull (const ros::Duration &dt)
 
void timeout_cb (const ros::TimerEvent &event)
 
bool wait_fetch_all ()
 
bool wait_param_set_ack_for (std::shared_ptr< ParamSetOpt > opt)
 

Private Attributes

const ros::Duration BOOTUP_TIME_DT
 
ros::ServiceServer get_srv
 
bool is_timedout
 
std::mutex list_cond_mutex
 
std::condition_variable list_receiving
 
const ros::Duration LIST_TIMEOUT_DT
 
std::recursive_mutex mutex
 
ssize_t param_count
 
ros::NodeHandle param_nh
 
size_t param_rx_retries
 
PR param_state
 
const ros::Duration PARAM_TIMEOUT_DT
 
ros::Publisher param_value_pub
 
std::unordered_map< std::string, Parameterparameters
 
std::list< uint16_t > parameters_missing_idx
 
ros::ServiceServer pull_srv
 
ros::ServiceServer push_srv
 
const int RETRIES_COUNT
 
std::unordered_map< std::string, std::shared_ptr< ParamSetOpt > > set_parameters
 
ros::ServiceServer set_srv
 
ros::Timer shedule_timer
 for startup shedule fetch More...
 
ros::Timer timeout_timer
 for timeout resend More...
 

Static Private Attributes

static constexpr int _RETRIES_COUNT = 3
 
static constexpr int BOOTUP_TIME_MS = 10000
 APM boot time. More...
 
static constexpr int LIST_TIMEOUT_MS = 30000
 Receive all time. More...
 
static constexpr int PARAM_TIMEOUT_MS = 1000
 Param wait time. More...
 

Additional Inherited Members

- Public Types inherited from mavros::plugin::PluginBase
using ConstPtr = boost::shared_ptr< PluginBase const >
 
using HandlerCb = mavconn::MAVConnInterface::ReceivedCb
 generic message handler callback More...
 
using HandlerInfo = std::tuple< mavlink::msgid_t, const char *, size_t, HandlerCb >
 Tuple: MSG ID, MSG NAME, message type into hash_code, message handler callback. More...
 
using Ptr = boost::shared_ptr< PluginBase >
 
using Subscriptions = std::vector< HandlerInfo >
 Subscriptions vector. More...
 
- Protected Member Functions inherited from mavros::plugin::PluginBase
void enable_connection_cb ()
 
template<class _C >
HandlerInfo make_handler (const mavlink::msgid_t id, void(_C::*fn)(const mavlink::mavlink_message_t *msg, const mavconn::Framing framing))
 
template<class _C , class _T >
HandlerInfo make_handler (void(_C::*fn)(const mavlink::mavlink_message_t *, _T &))
 
 PluginBase ()
 Plugin constructor Should not do anything before initialize() More...
 
- Protected Attributes inherited from mavros::plugin::PluginBase
UASm_uas
 

Detailed Description

Parameter manipulation plugin.

Definition at line 353 of file param.cpp.


The documentation for this class was generated from the following file:


mavros
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:11