Classes | Namespaces | Defines | Typedefs | Enumerations | Enumerator | Functions | Variables | Friends
Plugin

MAVROS Plugin system. More...

Classes

class  mavplugin::BatteryStatusDiag
class  mavplugin::CommandPlugin
 Command plugin. More...
class  mavplugin::CommandTransaction
class  mavplugin::DummyPlugin
 Dummy plugin. More...
class  mavplugin::FTPPlugin
 FTP plugin. More...
class  mavplugin::FTPRequest
 FTP Request message abstraction class. More...
class  mavplugin::GlobalPositionPlugin
 Global position plugin. More...
class  mavplugin::GPSInfo
class  mavplugin::GPSPlugin
 GPS plugin. More...
class  mavplugin::HeartbeatStatus
class  mavplugin::HwStatus
class  mavplugin::IMUPubPlugin
 IMU data publication plugin. More...
class  mavplugin::LocalPositionPlugin
 Local position plugin. Publish local position to TF and PositionStamped, send local position and visual position estimates to FCU. More...
class  mavplugin::MavRosPlugin
 MAVROS Plugin base class. More...
class  mavplugin::MemInfo
class  mavplugin::Parameter
 Parameter storage. More...
class  mavplugin::ParamPlugin
 Parameter manipulation plugin. More...
class  mavplugin::ParamSetOpt
 Parameter set transaction data. More...
struct  mavplugin::FTPRequest::PayloadHeader
 This is the payload which is in mavlink_file_transfer_protocol_t.payload. We pad the structure ourselves to 32 bit alignment to avoid usage of any pack pragmas. More...
class  mavplugin::RCIOPlugin
 RC IO plugin. More...
class  mavplugin::SafetyAreaPlugin
 Safety allopwed area plugin. More...
class  mavplugin::SetpointAccelerationPlugin
 Setpoint acceleration/force plugin. More...
class  mavplugin::SetpointAttitudePlugin
 Setpoint attitude plugin. More...
class  mavplugin::SetpointPositionPlugin
 Setpoint position plugin. More...
class  mavplugin::SetpointVelocityPlugin
 Setpoint velocity plugin. More...
class  mavplugin::SetPositionTargetLocalNEDMixin< D >
 This mixin adds set_position_target_local_ned() More...
class  mavplugin::SystemStatusDiag
class  mavplugin::SystemStatusPlugin
 System status plugin. Required for most applications. More...
class  mavplugin::SystemTimePlugin
class  mavplugin::TDRRadioPlugin
 3DR Radio plugin. More...
class  mavplugin::TDRRadioStatus
class  mavplugin::TFListenerMixin< D >
 This mixin adds TF listener to plugin. More...
class  mavplugin::TimeSyncStatus
class  mavplugin::VfrHudPlugin
 VFR HUD plugin. More...
class  mavplugin::WaypointItem
class  mavplugin::WaypointPlugin
 Mission manupulation plugin. More...

Namespaces

namespace  mavplugin

Defines

#define MESSAGE_HANDLER(_message_id, _class_method_ptr)   { _message_id, boost::bind(_class_method_ptr, this, _1, _2, _3) }
 Helper macros to define message handler map item.
#define SERVICE_IDLE_CHECK()

Typedefs

typedef boost::shared_ptr
< MavRosPlugin const > 
mavplugin::MavRosPlugin::ConstPtr
typedef std::lock_guard
< std::recursive_mutex > 
mavplugin::lock_guard
typedef boost::function< void(const
mavlink_message_t *msg,
uint8_t sysid, uint8_t compid) 
mavplugin::MavRosPlugin::message_handler )
typedef std::map< uint8_t,
message_handler > 
mavplugin::MavRosPlugin::message_map
typedef boost::any mavplugin::Parameter::param_t
typedef boost::shared_ptr
< MavRosPlugin > 
mavplugin::MavRosPlugin::Ptr
typedef std::unique_lock
< std::recursive_mutex > 
mavplugin::unique_lock
typedef std::vector< uint8_t > mavplugin::FTPPlugin::V_FileData
 This type used in servicies to store 'data' fileds.

Enumerations

enum  { mavplugin::ParamPlugin::PR_IDLE, mavplugin::ParamPlugin::PR_RXLIST, mavplugin::ParamPlugin::PR_RXPARAM, mavplugin::ParamPlugin::PR_TXPARAM }
enum  {
  mavplugin::WaypointPlugin::WP_IDLE, mavplugin::WaypointPlugin::WP_RXLIST, mavplugin::WaypointPlugin::WP_RXWP, mavplugin::WaypointPlugin::WP_TXLIST,
  mavplugin::WaypointPlugin::WP_TXWP, mavplugin::WaypointPlugin::WP_CLEAR, mavplugin::WaypointPlugin::WP_SET_CUR
}
enum  mavplugin::FTPRequest::ErrorCode {
  mavplugin::FTPRequest::kErrNone, mavplugin::FTPRequest::kErrFail, mavplugin::FTPRequest::kErrFailErrno, mavplugin::FTPRequest::kErrInvalidDataSize,
  mavplugin::FTPRequest::kErrInvalidSession, mavplugin::FTPRequest::kErrNoSessionsAvailable, mavplugin::FTPRequest::kErrEOF, mavplugin::FTPRequest::kErrUnknownCommand
}
 Error codes returned in Nak response. More...
enum  mavplugin::FTPRequest::Opcode {
  mavplugin::FTPRequest::kCmdNone, mavplugin::FTPRequest::kCmdTerminateSession, mavplugin::FTPRequest::kCmdResetSessions, mavplugin::FTPRequest::kCmdListDirectory,
  mavplugin::FTPRequest::kCmdOpenFileRO, mavplugin::FTPRequest::kCmdReadFile, mavplugin::FTPRequest::kCmdCreateFile, mavplugin::FTPRequest::kCmdWriteFile,
  mavplugin::FTPRequest::kCmdRemoveFile, mavplugin::FTPRequest::kCmdCreateDirectory, mavplugin::FTPRequest::kCmdRemoveDirectory, mavplugin::FTPRequest::kCmdOpenFileWO,
  mavplugin::FTPRequest::kCmdTruncateFile, mavplugin::FTPRequest::kCmdRename, mavplugin::FTPRequest::kCmdCalcFileCRC32, mavplugin::FTPRequest::kRspAck = 128,
  mavplugin::FTPRequest::kRspNak
}
 Command opcodes. More...
enum  mavplugin::FTPPlugin::OpState {
  mavplugin::FTPPlugin::OP_IDLE, mavplugin::FTPPlugin::OP_ACK, mavplugin::FTPPlugin::OP_LIST, mavplugin::FTPPlugin::OP_OPEN,
  mavplugin::FTPPlugin::OP_READ, mavplugin::FTPPlugin::OP_WRITE, mavplugin::FTPPlugin::OP_CHECKSUM
}

Functions

void mavplugin::SetpointAccelerationPlugin::accel_cb (const geometry_msgs::Vector3Stamped::ConstPtr &req)
void mavplugin::FTPPlugin::add_dirent (const char *ptr, size_t slen)
bool mavplugin::CommandPlugin::arming_cb (mavros::CommandBool::Request &req, mavros::CommandBool::Response &res)
 mavplugin::BatteryStatusDiag::BatteryStatusDiag (const std::string name)
static bool mavplugin::Parameter::check_exclude_param_id (std::string param_id)
bool mavplugin::FTPPlugin::checksum_cb (mavros::FileChecksum::Request &req, mavros::FileChecksum::Response &res)
void mavplugin::FTPPlugin::checksum_crc32_file (std::string &path)
void mavplugin::TimeSyncStatus::clear ()
bool mavplugin::WaypointPlugin::clear_cb (mavros::WaypointClear::Request &req, mavros::WaypointClear::Response &res)
bool mavplugin::FTPPlugin::close_cb (mavros::FileClose::Request &req, mavros::FileClose::Response &res)
bool mavplugin::FTPPlugin::close_file (std::string &path)
void mavplugin::CommandPlugin::command_int (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)
bool mavplugin::CommandPlugin::command_int_cb (mavros::CommandInt::Request &req, mavros::CommandInt::Response &res)
void mavplugin::CommandPlugin::command_long (uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
bool mavplugin::CommandPlugin::command_long_cb (mavros::CommandLong::Request &req, mavros::CommandLong::Response &res)
 mavplugin::CommandPlugin::CommandPlugin ()
 mavplugin::CommandTransaction::CommandTransaction (uint16_t command)
static constexpr int mavplugin::FTPPlugin::compute_rw_timeout (size_t len)
void mavplugin::RCIOPlugin::connection_cb (bool connected)
void mavplugin::WaypointPlugin::connection_cb (bool connected)
void mavplugin::ParamPlugin::connection_cb (bool connected)
void mavplugin::FTPPlugin::create_directory (std::string &path)
uint8_t * mavplugin::FTPRequest::data ()
char * mavplugin::FTPRequest::data_c ()
uint32_t * mavplugin::FTPRequest::data_u32 ()
bool mavplugin::FTPRequest::decode (UAS *uas, const mavlink_message_t *msg)
 Decode and check target system.
 mavplugin::DummyPlugin::DummyPlugin ()
void mavplugin::IMUPubPlugin::fill_imu_msg_attitude (sensor_msgs::ImuPtr &imu_msg, tf::Quaternion &orientation, double xg, double yg, double zg)
 fill imu/data message
void mavplugin::IMUPubPlugin::fill_imu_msg_raw (sensor_msgs::ImuPtr &imu_msg, double xg, double yg, double zg, double xa, double ya, double za)
 fill imu/data_raw message, store linear acceleration for imu/data
static WaypointItem mavplugin::WaypointItem::from_mission_item (mavlink_mission_item_t &mit)
static WaypointItem mavplugin::WaypointItem::from_msg (mavros::Waypoint &wp, uint16_t seq)
static param_t mavplugin::Parameter::from_param_value (mavlink_param_value_t &pmsg)
Parameter::param_t mavplugin::ParamPlugin::from_param_value (mavlink_param_value_t &msg)
static param_t mavplugin::Parameter::from_param_value_apm_quirk (mavlink_param_value_t &pmsg)
static param_t mavplugin::Parameter::from_xmlrpc_value (XmlRpc::XmlRpcValue &xml)
 mavplugin::FTPPlugin::FTPPlugin ()
 mavplugin::FTPRequest::FTPRequest ()
bool mavplugin::ParamPlugin::get_cb (mavros::ParamGet::Request &req, mavros::ParamGet::Response &res)
 get parameter ~param/get
std::string const mavplugin::DummyPlugin::get_name () const
std::string const mavplugin::VfrHudPlugin::get_name () const
 Plugin name (CamelCase)
const std::string mavplugin::SetpointVelocityPlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::RCIOPlugin::get_name () const
 Plugin name (CamelCase)
const std::string mavplugin::SetpointAccelerationPlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::LocalPositionPlugin::get_name () const
 Plugin name (CamelCase)
const std::string mavplugin::SetpointPositionPlugin::get_name () const
 Plugin name (CamelCase)
virtual const std::string mavplugin::MavRosPlugin::get_name () const =0
 Plugin name (CamelCase)
std::string const mavplugin::GlobalPositionPlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::IMUPubPlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::CommandPlugin::get_name () const
 Plugin name (CamelCase)
const std::string mavplugin::SafetyAreaPlugin::get_name () const
 Plugin name (CamelCase)
const std::string mavplugin::SetpointAttitudePlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::TDRRadioPlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::GPSPlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::SystemTimePlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::WaypointPlugin::get_name () const
 Plugin name (CamelCase)
std::string const mavplugin::ParamPlugin::get_name () const
 Plugin name (CamelCase)
const std::string mavplugin::SystemStatusPlugin::get_name () const
 Plugin name (CamelCase)
const message_map mavplugin::VfrHudPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::SetpointVelocityPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::DummyPlugin::get_rx_handlers ()
const message_map mavplugin::RCIOPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::SetpointAccelerationPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::LocalPositionPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::SetpointPositionPlugin::get_rx_handlers ()
 Return map with message rx handlers.
virtual const message_map mavplugin::MavRosPlugin::get_rx_handlers ()=0
 Return map with message rx handlers.
const message_map mavplugin::GlobalPositionPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::IMUPubPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::CommandPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::SafetyAreaPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::SetpointAttitudePlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::TDRRadioPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::GPSPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::SystemTimePlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::WaypointPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::ParamPlugin::get_rx_handlers ()
 Return map with message rx handlers.
const message_map mavplugin::SystemStatusPlugin::get_rx_handlers ()
 Return map with message rx handlers.
uint8_t mavplugin::FTPRequest::get_target_system_id ()
 mavplugin::GlobalPositionPlugin::GlobalPositionPlugin ()
void mavplugin::WaypointPlugin::go_idle (void)
void mavplugin::FTPPlugin::go_idle (bool is_error_, int r_errno_=0)
 Go to IDLE mode.
void mavplugin::ParamPlugin::go_idle ()
bool mavplugin::WaypointPlugin::goto_cb (mavros::WaypointGOTO::Request &req, mavros::WaypointGOTO::Response &res)
 mavplugin::GPSInfo::GPSInfo (const std::string name)
 mavplugin::GPSPlugin::GPSPlugin ()
bool mavplugin::CommandPlugin::guided_cb (mavros::CommandBool::Request &req, mavros::CommandBool::Response &res)
void mavplugin::FTPPlugin::handle_ack_checksum (FTPRequest &req)
void mavplugin::FTPPlugin::handle_ack_list (FTPRequest &req)
void mavplugin::FTPPlugin::handle_ack_open (FTPRequest &req)
void mavplugin::FTPPlugin::handle_ack_read (FTPRequest &req)
void mavplugin::FTPPlugin::handle_ack_write (FTPRequest &req)
void mavplugin::IMUPubPlugin::handle_attitude (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::IMUPubPlugin::handle_attitude_quaternion (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::CommandPlugin::handle_command_ack (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::FTPPlugin::handle_file_transfer_protocol (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::GlobalPositionPlugin::handle_global_position_int (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::GPSPlugin::handle_gps_raw_int (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::GPSPlugin::handle_gps_status (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::DummyPlugin::handle_heartbeat (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::SystemStatusPlugin::handle_heartbeat (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::IMUPubPlugin::handle_highres_imu (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::LocalPositionPlugin::handle_local_position_ned (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
template<typename msgT >
void mavplugin::TDRRadioPlugin::handle_message (msgT &rst, uint8_t sysid, uint8_t compid)
void mavplugin::WaypointPlugin::handle_mission_ack (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::WaypointPlugin::handle_mission_count (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::WaypointPlugin::handle_mission_current (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::WaypointPlugin::handle_mission_item (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::WaypointPlugin::handle_mission_item_reached (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::WaypointPlugin::handle_mission_request (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::ParamPlugin::handle_param_value (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::TDRRadioPlugin::handle_radio_status (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::IMUPubPlugin::handle_raw_imu (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::RCIOPlugin::handle_rc_channels (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::RCIOPlugin::handle_rc_channels_raw (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::FTPPlugin::handle_req_ack (FTPRequest &req)
void mavplugin::FTPPlugin::handle_req_nack (FTPRequest &req)
void mavplugin::IMUPubPlugin::handle_scaled_imu (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::IMUPubPlugin::handle_scaled_pressure (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::RCIOPlugin::handle_servo_output_raw (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::DummyPlugin::handle_statustext (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::SystemStatusPlugin::handle_statustext (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::DummyPlugin::handle_sys_status (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::SystemStatusPlugin::handle_sys_status (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::SystemTimePlugin::handle_system_time (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
void mavplugin::VfrHudPlugin::handle_vfr_hud (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid)
PayloadHeader * mavplugin::FTPRequest::header ()
void mavplugin::SystemStatusPlugin::heartbeat_cb (const ros::TimerEvent &event)
 mavplugin::HeartbeatStatus::HeartbeatStatus (const std::string name, size_t win_size)
 mavplugin::HwStatus::HwStatus (const std::string name)
 mavplugin::IMUPubPlugin::IMUPubPlugin ()
void mavplugin::SafetyAreaPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::VfrHudPlugin::initialize (UAS &uas, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
void mavplugin::DummyPlugin::initialize (UAS &uas, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
void mavplugin::LocalPositionPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::RCIOPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::SetpointVelocityPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::SetpointPositionPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::SetpointAccelerationPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::SetpointAttitudePlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::IMUPubPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::GlobalPositionPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::CommandPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
virtual void mavplugin::MavRosPlugin::initialize (UAS &uas, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)=0
 Plugin initializer.
void mavplugin::TDRRadioPlugin::initialize (UAS &uas, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::GPSPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::SystemTimePlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::WaypointPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::SystemStatusPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
void mavplugin::ParamPlugin::initialize (UAS &uas_, ros::NodeHandle &nh, diagnostic_updater::Updater &diag_updater)
 Plugin initializer.
bool mavplugin::SetpointAttitudePlugin::is_normalized (float throttle, const float min, const float max)
bool mavplugin::CommandPlugin::land_cb (mavros::CommandTOL::Request &req, mavros::CommandTOL::Response &res)
bool mavplugin::FTPPlugin::list_cb (mavros::FileList::Request &req, mavros::FileList::Response &res)
void mavplugin::FTPPlugin::list_directory (std::string &path)
void mavplugin::FTPPlugin::list_directory_end ()
 mavplugin::LocalPositionPlugin::LocalPositionPlugin ()
 mavplugin::MavRosPlugin::MavRosPlugin (const MavRosPlugin &)
 mavplugin::MavRosPlugin::MavRosPlugin ()
 Plugin constructor Should not do anything before initialize()
 mavplugin::MemInfo::MemInfo (const std::string name)
void mavplugin::WaypointPlugin::mission_ack (enum MAV_MISSION_RESULT type)
void mavplugin::WaypointPlugin::mission_clear_all ()
void mavplugin::WaypointPlugin::mission_count (uint16_t cnt)
void mavplugin::WaypointPlugin::mission_item (WaypointItem &wp)
void mavplugin::WaypointPlugin::mission_request (uint16_t seq)
void mavplugin::WaypointPlugin::mission_request_list ()
void mavplugin::WaypointPlugin::mission_set_current (uint16_t seq)
bool mavplugin::FTPPlugin::mkdir_cb (mavros::FileMakeDir::Request &req, mavros::FileMakeDir::Response &res)
bool mavplugin::FTPPlugin::open_cb (mavros::FileOpen::Request &req, mavros::FileOpen::Response &res)
bool mavplugin::FTPPlugin::open_file (std::string &path, int mode)
void mavplugin::RCIOPlugin::override_cb (const mavros::OverrideRCIn::ConstPtr req)
void mavplugin::ParamPlugin::param_request_list ()
void mavplugin::ParamPlugin::param_request_read (std::string id, int16_t index=-1)
void mavplugin::ParamPlugin::param_set (Parameter &param)
 mavplugin::ParamPlugin::ParamPlugin ()
 mavplugin::ParamSetOpt::ParamSetOpt (Parameter &_p, size_t _rem)
void mavplugin::SetpointAttitudePlugin::pose_cb (const geometry_msgs::PoseStamped::ConstPtr &req)
void mavplugin::SetpointAttitudePlugin::pose_cov_cb (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &req)
void mavplugin::SystemStatusPlugin::process_statustext_apm_quirk (uint8_t severity, std::string &text)
void mavplugin::SystemStatusPlugin::process_statustext_normal (uint8_t severity, std::string &text)
void mavplugin::WaypointPlugin::publish_waypoints ()
bool mavplugin::WaypointPlugin::pull_cb (mavros::WaypointPull::Request &req, mavros::WaypointPull::Response &res)
bool mavplugin::ParamPlugin::pull_cb (mavros::ParamPull::Request &req, mavros::ParamPull::Response &res)
 fetches all parameters from device ~param/pull
bool mavplugin::WaypointPlugin::push_cb (mavros::WaypointPush::Request &req, mavros::WaypointPush::Response &res)
bool mavplugin::ParamPlugin::push_cb (mavros::ParamPush::Request &req, mavros::ParamPush::Response &res)
 push all parameter value to device ~param/push
uint8_t * mavplugin::FTPRequest::raw_payload ()
void mavplugin::RCIOPlugin::rc_channels_override (const boost::array< uint16_t, 8 > &channels)
 mavplugin::RCIOPlugin::RCIOPlugin ()
bool mavplugin::FTPPlugin::read_cb (mavros::FileRead::Request &req, mavros::FileRead::Response &res)
bool mavplugin::FTPPlugin::read_file (std::string &path, size_t off, size_t len)
void mavplugin::FTPPlugin::read_file_end ()
bool mavplugin::FTPPlugin::remove_cb (mavros::FileRemove::Request &req, mavros::FileRemove::Response &res)
void mavplugin::FTPPlugin::remove_directory (std::string &path)
void mavplugin::FTPPlugin::remove_file (std::string &path)
bool mavplugin::FTPPlugin::rename_ (std::string &old_path, std::string &new_path)
bool mavplugin::FTPPlugin::rename_cb (mavros::FileRename::Request &req, mavros::FileRename::Response &res)
void mavplugin::WaypointPlugin::request_mission_done (void)
bool mavplugin::FTPPlugin::reset_cb (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 Reset communication on both sides.
void mavplugin::WaypointPlugin::restart_timeout_timer (void)
void mavplugin::ParamPlugin::restart_timeout_timer ()
void mavplugin::WaypointPlugin::restart_timeout_timer_int (void)
bool mavplugin::FTPPlugin::rmdir_cb (mavros::FileRemoveDir::Request &req, mavros::FileRemoveDir::Response &res)
void mavplugin::GPSInfo::run (diagnostic_updater::DiagnosticStatusWrapper &stat)
void mavplugin::TimeSyncStatus::run (diagnostic_updater::DiagnosticStatusWrapper &stat)
void mavplugin::SystemStatusDiag::run (diagnostic_updater::DiagnosticStatusWrapper &stat)
void mavplugin::BatteryStatusDiag::run (diagnostic_updater::DiagnosticStatusWrapper &stat)
void mavplugin::MemInfo::run (diagnostic_updater::DiagnosticStatusWrapper &stat)
void mavplugin::HwStatus::run (diagnostic_updater::DiagnosticStatusWrapper &stat)
void mavplugin::SafetyAreaPlugin::safety_set_allowed_area (uint8_t coordinate_frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
void mavplugin::SafetyAreaPlugin::safetyarea_cb (const geometry_msgs::PolygonStamped::ConstPtr &req)
 mavplugin::SafetyAreaPlugin::SafetyAreaPlugin ()
void mavplugin::FTPRequest::send (UAS *uas, uint16_t seqNumber)
 Encode and send message.
void mavplugin::FTPPlugin::send_any_path_command (FTPRequest::Opcode op, const std::string debug_msg, std::string &path, uint32_t offset)
 Send any command with string payload (usually file/dir path)
void mavplugin::SetpointAttitudePlugin::send_attitude_ang_velocity (const ros::Time &stamp, const float vx, const float vy, const float vz)
void mavplugin::SetpointAttitudePlugin::send_attitude_throttle (const float throttle)
void mavplugin::SetpointAttitudePlugin::send_attitude_transform (const tf::Transform &transform, const ros::Time &stamp)
void mavplugin::FTPPlugin::send_calc_file_crc32_command (std::string &path)
bool mavplugin::CommandPlugin::send_command_int (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 mavplugin::CommandPlugin::send_command_long_and_wait (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)
void mavplugin::FTPPlugin::send_create_command ()
void mavplugin::FTPPlugin::send_create_dir_command (std::string &path)
void mavplugin::FTPPlugin::send_list_command ()
void mavplugin::FTPPlugin::send_open_ro_command ()
void mavplugin::FTPPlugin::send_open_wo_command ()
bool mavplugin::ParamPlugin::send_param_set_and_wait (Parameter &param)
void mavplugin::FTPPlugin::send_read_command ()
void mavplugin::FTPPlugin::send_remove_command (std::string &path)
void mavplugin::FTPPlugin::send_remove_dir_command (std::string &path)
bool mavplugin::FTPPlugin::send_rename_command (std::string &old_path, std::string &new_path)
void mavplugin::FTPPlugin::send_reset ()
void mavplugin::SafetyAreaPlugin::send_safety_set_allowed_area (float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
void mavplugin::SetpointAccelerationPlugin::send_setpoint_acceleration (const ros::Time &stamp, float afx, float afy, float afz)
void mavplugin::SetpointPositionPlugin::send_setpoint_transform (const tf::Transform &transform, const ros::Time &stamp)
void mavplugin::SetpointVelocityPlugin::send_setpoint_velocity (const ros::Time &stamp, float vx, float vy, float vz, float yaw_rate)
void mavplugin::FTPPlugin::send_terminate_command (uint32_t session)
void mavplugin::FTPPlugin::send_truncate_command (std::string &path, size_t length)
void mavplugin::WaypointPlugin::send_waypoint (size_t seq)
void mavplugin::FTPPlugin::send_write_command (const size_t bytes_to_copy)
void mavplugin::SystemStatusDiag::set (mavlink_sys_status_t &st)
void mavplugin::BatteryStatusDiag::set (float volt, float curr, float rem)
void mavplugin::MemInfo::set (uint16_t f, uint16_t b)
void mavplugin::HwStatus::set (uint16_t v, uint8_t e)
void mavplugin::SetpointAttitudePlugin::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)
bool mavplugin::ParamPlugin::set_cb (mavros::ParamSet::Request &req, mavros::ParamSet::Response &res)
 sets parameter value ~param/set
bool mavplugin::WaypointPlugin::set_cur_cb (mavros::WaypointSetCurrent::Request &req, mavros::WaypointSetCurrent::Response &res)
void mavplugin::WaypointPlugin::set_current_waypoint (size_t seq)
void mavplugin::FTPRequest::set_data_string (std::string &s)
 Copy string to payload.
void mavplugin::GPSInfo::set_gps_raw (mavlink_gps_raw_int_t &gps)
bool mavplugin::CommandPlugin::set_home_cb (mavros::CommandHome::Request &req, mavros::CommandHome::Response &res)
void mavplugin::BatteryStatusDiag::set_min_voltage (float volt)
bool mavplugin::SystemStatusPlugin::set_mode_cb (mavros::SetMode::Request &req, mavros::SetMode::Response &res)
void mavplugin::SetPositionTargetLocalNEDMixin< D >::set_position_target_local_ned (uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
bool mavplugin::SystemStatusPlugin::set_rate_cb (mavros::StreamRate::Request &req, mavros::StreamRate::Response &res)
void mavplugin::TimeSyncStatus::set_timestamp (uint64_t timestamp_us)
void mavplugin::SetpointPositionPlugin::setpoint_cb (const geometry_msgs::PoseStamped::ConstPtr &req)
 mavplugin::SetpointAccelerationPlugin::SetpointAccelerationPlugin ()
 mavplugin::SetpointAttitudePlugin::SetpointAttitudePlugin ()
 mavplugin::SetpointPositionPlugin::SetpointPositionPlugin ()
 mavplugin::SetpointVelocityPlugin::SetpointVelocityPlugin ()
void mavplugin::IMUPubPlugin::setup_covariance (boost::array< double, 9 > &cov, double stdev)
void mavplugin::ParamPlugin::shedule_cb (const ros::TimerEvent &event)
void mavplugin::WaypointPlugin::shedule_pull (const ros::Duration &dt)
void mavplugin::ParamPlugin::shedule_pull (const ros::Duration &dt)
void mavplugin::WaypointPlugin::sheduled_pull_cb (const ros::TimerEvent &event)
void mavplugin::SystemTimePlugin::sys_time_cb (const ros::TimerEvent &event)
 mavplugin::SystemStatusDiag::SystemStatusDiag (const std::string name)
 mavplugin::SystemStatusPlugin::SystemStatusPlugin ()
 mavplugin::SystemTimePlugin::SystemTimePlugin ()
bool mavplugin::CommandPlugin::takeoff_cb (mavros::CommandTOL::Request &req, mavros::CommandTOL::Response &res)
 mavplugin::TDRRadioPlugin::TDRRadioPlugin ()
 mavplugin::TDRRadioStatus::TDRRadioStatus (const std::string name, uint8_t _low_rssi)
void mavplugin::TFListenerMixin< D >::tf_listener (void)
void mavplugin::TFListenerMixin< D >::tf_start (const char *_thd_name, void(D::*cbp)(const tf::Transform &, const ros::Time &))
 start tf listener
void mavplugin::SetpointAttitudePlugin::throttle_cb (const std_msgs::Float64::ConstPtr &req)
void mavplugin::TimeSyncStatus::tick (int64_t dt, uint64_t timestamp_us)
void mavplugin::WaypointPlugin::timeout_cb (const ros::TimerEvent &event)
void mavplugin::SystemStatusPlugin::timeout_cb (const ros::TimerEvent &event)
void mavplugin::ParamPlugin::timeout_cb (const ros::TimerEvent &event)
 mavplugin::TimeSyncStatus::TimeSyncStatus (const std::string name, size_t win_size)
static int64_t mavplugin::Parameter::to_integer (param_t &p)
static mavros::Waypoint mavplugin::WaypointItem::to_msg (WaypointItem &wp)
static mavlink_param_union_t mavplugin::Parameter::to_param_union (param_t p)
mavlink_param_union_t mavplugin::ParamPlugin::to_param_union (Parameter::param_t p)
static mavlink_param_union_t mavplugin::Parameter::to_param_union_apm_quirk (param_t p)
static double mavplugin::Parameter::to_real (param_t &p)
static std::string mavplugin::WaypointItem::to_string_command (WaypointItem &wpi)
static std::string mavplugin::WaypointItem::to_string_frame (WaypointItem &wpi)
static std::string mavplugin::Parameter::to_string_vt (param_t p)
static XmlRpc::XmlRpcValue mavplugin::Parameter::to_xmlrpc_value (param_t &p)
bool mavplugin::FTPPlugin::truncate_cb (mavros::FileTruncate::Request &req, mavros::FileTruncate::Response &res)
void mavplugin::FTPPlugin::truncate_file (std::string &path, size_t length)
void mavplugin::SetpointAttitudePlugin::twist_cb (const geometry_msgs::TwistStamped::ConstPtr &req)
void mavplugin::IMUPubPlugin::uas_store_attitude (tf::Quaternion &orientation, geometry_msgs::Vector3 &gyro_vec, geometry_msgs::Vector3 &acc_vec)
void mavplugin::SetpointVelocityPlugin::vel_cb (const geometry_msgs::TwistStamped::ConstPtr &req)
 mavplugin::VfrHudPlugin::VfrHudPlugin ()
bool mavplugin::CommandPlugin::wait_ack_for (CommandTransaction *tr)
bool mavplugin::FTPPlugin::wait_completion (const int msecs)
bool mavplugin::WaypointPlugin::wait_fetch_all ()
bool mavplugin::ParamPlugin::wait_fetch_all ()
bool mavplugin::ParamPlugin::wait_param_set_ack_for (ParamSetOpt *opt)
bool mavplugin::WaypointPlugin::wait_push_all ()
 mavplugin::WaypointPlugin::WaypointPlugin ()
size_t mavplugin::FTPPlugin::write_bytes_to_copy ()
bool mavplugin::FTPPlugin::write_cb (mavros::FileWrite::Request &req, mavros::FileWrite::Response &res)
bool mavplugin::FTPPlugin::write_file (std::string &path, size_t off, V_FileData &data)
void mavplugin::FTPPlugin::write_file_end ()
virtual mavplugin::MavRosPlugin::~MavRosPlugin ()

Variables

ros::Subscriber mavplugin::SetpointAccelerationPlugin::accel_sub
std::condition_variable mavplugin::CommandTransaction::ack
std::condition_variable mavplugin::ParamSetOpt::ack
const ros::Duration mavplugin::CommandPlugin::ACK_TIMEOUT_DT
static constexpr int mavplugin::CommandPlugin::ACK_TIMEOUT_MS = 5000
std::list< CommandTransaction * > mavplugin::CommandPlugin::ack_waiting_list
uint32_t mavplugin::FTPPlugin::active_session
 session id of current operation
boost::array< double, 9 > mavplugin::IMUPubPlugin::angular_velocity_cov
ros::ServiceServer mavplugin::CommandPlugin::arming_srv
ros::Subscriber mavplugin::SetpointAttitudePlugin::att_sub
bool mavplugin::WaypointItem::autocontinue
BatteryStatusDiag mavplugin::SystemStatusPlugin::batt_diag
ros::Publisher mavplugin::SystemStatusPlugin::batt_pub
const ros::Duration mavplugin::WaypointPlugin::BOOTUP_TIME_DT
const ros::Duration mavplugin::ParamPlugin::BOOTUP_TIME_DT
static constexpr int mavplugin::WaypointPlugin::BOOTUP_TIME_MS = 15000
static constexpr int mavplugin::ParamPlugin::BOOTUP_TIME_MS = 10000
 APM boot time.
uint16_t mavplugin::MemInfo::brkval
uint32_t mavplugin::FTPPlugin::checksum_crc32
ros::ServiceServer mavplugin::FTPPlugin::checksum_srv
std::string mavplugin::LocalPositionPlugin::child_frame_id
 frame for TF and Pose
std::string mavplugin::SetpointPositionPlugin::child_frame_id
std::string mavplugin::GlobalPositionPlugin::child_frame_id
 frame for TF and Pose
std::string mavplugin::SetpointAttitudePlugin::child_frame_id
static constexpr int mavplugin::FTPPlugin::CHUNK_TIMEOUT_MS = 200
ros::ServiceServer mavplugin::WaypointPlugin::clear_srv
ros::ServiceServer mavplugin::FTPPlugin::close_srv
ros::NodeHandle mavplugin::CommandPlugin::cmd_nh
enum MAV_CMD mavplugin::WaypointItem::command
ros::ServiceServer mavplugin::CommandPlugin::command_int_srv
ros::ServiceServer mavplugin::CommandPlugin::command_long_srv
std::condition_variable mavplugin::FTPPlugin::cond
 wait condvar
std::mutex mavplugin::CommandTransaction::cond_mutex
std::mutex mavplugin::FTPPlugin::cond_mutex
std::mutex mavplugin::ParamSetOpt::cond_mutex
int mavplugin::TimeSyncStatus::count_
uint8_t mavplugin::WaypointItem::current
float mavplugin::BatteryStatusDiag::current
uint8_t mavplugin::FTPRequest::PayloadHeader::data []
 command data, varies by Opcode
static const uint8_t mavplugin::FTPRequest::DATA_MAXSZ = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(PayloadHeader)
bool mavplugin::TDRRadioStatus::data_received
static const char mavplugin::FTPRequest::DIRENT_DIR = 'D'
static const char mavplugin::FTPRequest::DIRENT_FILE = 'F'
static const char mavplugin::FTPRequest::DIRENT_SKIP = 'S'
bool mavplugin::WaypointPlugin::do_pull_after_gcs
TimeSyncStatus mavplugin::SystemTimePlugin::dt_diag
int64_t mavplugin::TimeSyncStatus::dt_sum
std::atomic< uint16_t > mavplugin::GPSInfo::eph
std::atomic< uint16_t > mavplugin::GPSInfo::epv
uint16_t mavplugin::CommandTransaction::expected_command
ros::Publisher mavplugin::GlobalPositionPlugin::fix_pub
ros::Publisher mavplugin::GPSPlugin::fix_pub
std::atomic< int > mavplugin::GPSInfo::fix_type
enum MAV_FRAME mavplugin::WaypointItem::frame
std::string mavplugin::LocalPositionPlugin::frame_id
 origin for TF
std::string mavplugin::SetpointPositionPlugin::frame_id
std::string mavplugin::IMUPubPlugin::frame_id
std::string mavplugin::GlobalPositionPlugin::frame_id
 origin for TF
std::string mavplugin::SetpointAttitudePlugin::frame_id
std::string mavplugin::GPSPlugin::frame_id
std::string mavplugin::SystemTimePlugin::frame_id
ssize_t mavplugin::MemInfo::freemem
ros::NodeHandle mavplugin::FTPPlugin::ftp_nh
static constexpr double mavplugin::IMUPubPlugin::GAUSS_TO_TESLA = 1.0e-4
ros::ServiceServer mavplugin::ParamPlugin::get_srv
ros::ServiceServer mavplugin::WaypointPlugin::goto_srv
ros::NodeHandle mavplugin::GlobalPositionPlugin::gp_nh
GPSInfo mavplugin::GPSPlugin::gps_diag
ros::ServiceServer mavplugin::CommandPlugin::guided_srv
bool mavplugin::IMUPubPlugin::has_att_quat
bool mavplugin::IMUPubPlugin::has_hr_imu
bool mavplugin::TDRRadioPlugin::has_radio_status
bool mavplugin::RCIOPlugin::has_rc_channels_msg
bool mavplugin::IMUPubPlugin::has_scaled_imu
HeartbeatStatus mavplugin::SystemStatusPlugin::hb_diag
ros::Publisher mavplugin::GlobalPositionPlugin::hdg_pub
ros::Timer mavplugin::SystemStatusPlugin::heartbeat_timer
int mavplugin::HeartbeatStatus::hist_indx_
int mavplugin::TimeSyncStatus::hist_indx_
HwStatus mavplugin::SystemStatusPlugin::hwst_diag
size_t mavplugin::HwStatus::i2cerr
size_t mavplugin::HwStatus::i2cerr_last
ros::Publisher mavplugin::IMUPubPlugin::imu_pub
ros::Publisher mavplugin::IMUPubPlugin::imu_raw_pub
bool mavplugin::FTPPlugin::is_error
 error signaling flag (timeout/proto error)
bool mavplugin::WaypointPlugin::is_timedout
bool mavplugin::ParamSetOpt::is_timedout
bool mavplugin::ParamPlugin::is_timedout
ros::ServiceServer mavplugin::CommandPlugin::land_srv
int64_t mavplugin::TimeSyncStatus::last_dt
mavlink_heartbeat_t mavplugin::HeartbeatStatus::last_hb
mavlink_radio_status_t mavplugin::TDRRadioStatus::last_rst
uint16_t mavplugin::FTPPlugin::last_send_seqnr
 seqNumber for send.
mavlink_sys_status_t mavplugin::SystemStatusDiag::last_st
uint64_t mavplugin::TimeSyncStatus::last_ts
geometry_msgs::Vector3 mavplugin::IMUPubPlugin::linear_accel_vec
boost::array< double, 9 > mavplugin::IMUPubPlugin::linear_acceleration_cov
std::mutex mavplugin::ParamPlugin::list_cond_mutex
std::vector< mavros::FileEntry > mavplugin::FTPPlugin::list_entries
uint32_t mavplugin::FTPPlugin::list_offset
std::string mavplugin::FTPPlugin::list_path
std::condition_variable mavplugin::WaypointPlugin::list_receiving
std::condition_variable mavplugin::ParamPlugin::list_receiving
std::condition_variable mavplugin::WaypointPlugin::list_sending
ros::ServiceServer mavplugin::FTPPlugin::list_srv
const ros::Duration mavplugin::WaypointPlugin::LIST_TIMEOUT_DT
const ros::Duration mavplugin::ParamPlugin::LIST_TIMEOUT_DT
static constexpr int mavplugin::WaypointPlugin::LIST_TIMEOUT_MS = 30000
 system startup delay before start pull
static constexpr int mavplugin::FTPPlugin::LIST_TIMEOUT_MS = 5000
static constexpr int mavplugin::ParamPlugin::LIST_TIMEOUT_MS = 30000
 Receive all time.
ros::Publisher mavplugin::LocalPositionPlugin::local_position
const uint8_t mavplugin::TDRRadioStatus::low_rssi
ros::Publisher mavplugin::IMUPubPlugin::magn_pub
boost::array< double, 9 > mavplugin::IMUPubPlugin::magnetic_cov
const double mavplugin::HeartbeatStatus::max_freq_
const double mavplugin::TimeSyncStatus::max_freq_
static constexpr size_t mavplugin::FTPPlugin::MAX_RESERVE_DIFF = 0x10000
 Maximum difference between allocated space and used.
MemInfo mavplugin::SystemStatusPlugin::mem_diag
static constexpr double mavplugin::IMUPubPlugin::MILLIBAR_TO_PASCAL = 1.0e2
static constexpr double mavplugin::IMUPubPlugin::MILLIG_TO_MS2 = 9.80665 / 1000.0
static constexpr double mavplugin::IMUPubPlugin::MILLIRS_TO_RADSEC = 1.0e-3
static constexpr double mavplugin::IMUPubPlugin::MILLIT_TO_TESLA = 1000.0
const double mavplugin::HeartbeatStatus::min_freq_
const double mavplugin::TimeSyncStatus::min_freq_
float mavplugin::BatteryStatusDiag::min_voltage
ros::ServiceServer mavplugin::FTPPlugin::mkdir_srv
ros::ServiceServer mavplugin::SystemStatusPlugin::mode_srv
std::recursive_mutex mavplugin::RCIOPlugin::mutex
std::recursive_mutex mavplugin::CommandPlugin::mutex
std::recursive_mutex mavplugin::HeartbeatStatus::mutex
std::recursive_mutex mavplugin::TimeSyncStatus::mutex
std::recursive_mutex mavplugin::SystemStatusDiag::mutex
std::recursive_mutex mavplugin::WaypointPlugin::mutex
std::recursive_mutex mavplugin::BatteryStatusDiag::mutex
std::recursive_mutex mavplugin::MemInfo::mutex
std::recursive_mutex mavplugin::HwStatus::mutex
std::recursive_mutex mavplugin::ParamPlugin::mutex
uint32_t mavplugin::FTPRequest::PayloadHeader::offset
 Offsets for List and Read commands.
OpState mavplugin::FTPPlugin::op_state
uint8_t mavplugin::FTPRequest::PayloadHeader::opcode
 Command opcode.
std::string mavplugin::FTPPlugin::open_path
size_t mavplugin::FTPPlugin::open_size
ros::ServiceServer mavplugin::FTPPlugin::open_srv
static constexpr int mavplugin::FTPPlugin::OPEN_TIMEOUT_MS = 200
boost::array< double, 9 > mavplugin::IMUPubPlugin::orientation_cov
ros::Subscriber mavplugin::RCIOPlugin::override_sub
uint8_t mavplugin::FTPRequest::PayloadHeader::padding [2]
 32 bit aligment padding
Parameter mavplugin::ParamSetOpt::param
float mavplugin::WaypointItem::param1
float mavplugin::WaypointItem::param2
float mavplugin::WaypointItem::param3
float mavplugin::WaypointItem::param4
uint16_t mavplugin::Parameter::param_count
ssize_t mavplugin::ParamPlugin::param_count
std::string mavplugin::Parameter::param_id
uint16_t mavplugin::Parameter::param_index
ros::NodeHandle mavplugin::ParamPlugin::param_nh
size_t mavplugin::ParamPlugin::param_rx_retries
enum mavplugin::ParamPlugin:: { ... }  mavplugin::ParamPlugin::param_state
const ros::Duration mavplugin::ParamPlugin::PARAM_TIMEOUT_DT
static constexpr int mavplugin::ParamPlugin::PARAM_TIMEOUT_MS = 1000
 Param wait time.
param_t mavplugin::Parameter::param_value
std::map< std::string, Parameter > mavplugin::ParamPlugin::parameters
std::list< uint16_t > mavplugin::ParamPlugin::parameters_missing_idx
ros::NodeHandle mavplugin::LocalPositionPlugin::pos_nh
ros::Publisher mavplugin::GlobalPositionPlugin::pos_pub
ros::Publisher mavplugin::IMUPubPlugin::press_pub
ros::ServiceServer mavplugin::WaypointPlugin::pull_srv
ros::ServiceServer mavplugin::ParamPlugin::pull_srv
ros::ServiceServer mavplugin::WaypointPlugin::push_srv
ros::ServiceServer mavplugin::ParamPlugin::push_srv
int mavplugin::FTPPlugin::r_errno
 store errno from server
ros::ServiceServer mavplugin::SystemStatusPlugin::rate_srv
std::vector< uint16_t > mavplugin::RCIOPlugin::raw_rc_in
std::vector< uint16_t > mavplugin::RCIOPlugin::raw_rc_out
ros::Publisher mavplugin::RCIOPlugin::rc_in_pub
ros::NodeHandle mavplugin::RCIOPlugin::rc_nh
ros::Publisher mavplugin::RCIOPlugin::rc_out_pub
V_FileData mavplugin::FTPPlugin::read_buffer
uint32_t mavplugin::FTPPlugin::read_offset
size_t mavplugin::FTPPlugin::read_size
ros::ServiceServer mavplugin::FTPPlugin::read_srv
std::mutex mavplugin::WaypointPlugin::recv_cond_mutex
ros::Publisher mavplugin::GlobalPositionPlugin::rel_alt_pub
float mavplugin::BatteryStatusDiag::remaining
ros::ServiceServer mavplugin::FTPPlugin::remove_srv
ros::ServiceServer mavplugin::FTPPlugin::rename_srv
uint8_t mavplugin::FTPRequest::PayloadHeader::req_opcode
 Request opcode returned in kRspAck, kRspNak message.
ros::ServiceServer mavplugin::FTPPlugin::reset_srv
const ros::Duration mavplugin::WaypointPlugin::RESHEDULE_DT
static constexpr int mavplugin::WaypointPlugin::RESHEDULE_MS = 5000
bool mavplugin::WaypointPlugin::reshedule_pull
uint8_t mavplugin::CommandTransaction::result
static constexpr int mavplugin::WaypointPlugin::RETRIES_COUNT = 3
static constexpr int mavplugin::ParamPlugin::RETRIES_COUNT = 3
size_t mavplugin::ParamSetOpt::retries_remaining
bool mavplugin::SetpointAttitudePlugin::reverse_throttle
ros::ServiceServer mavplugin::FTPPlugin::rmdir_srv
double mavplugin::GlobalPositionPlugin::rot_cov
ros::NodeHandle mavplugin::SafetyAreaPlugin::safety_nh
ros::Subscriber mavplugin::SafetyAreaPlugin::safetyarea_sub
std::atomic< int > mavplugin::GPSInfo::satellites_visible
std::mutex mavplugin::WaypointPlugin::send_cond_mutex
bool mavplugin::SetpointAccelerationPlugin::send_force
bool mavplugin::LocalPositionPlugin::send_tf
bool mavplugin::GlobalPositionPlugin::send_tf
std::vector< WaypointItem > mavplugin::WaypointPlugin::send_waypoints
uint16_t mavplugin::WaypointItem::seq
std::vector< int > mavplugin::HeartbeatStatus::seq_nums_
std::vector< int > mavplugin::TimeSyncStatus::seq_nums_
uint16_t mavplugin::FTPRequest::PayloadHeader::seqNumber
 sequence number for message
uint8_t mavplugin::FTPRequest::PayloadHeader::session
 Session id for read and write commands.
std::map< std::string, uint32_t > mavplugin::FTPPlugin::session_file_map
ros::ServiceServer mavplugin::WaypointPlugin::set_cur_srv
ros::ServiceServer mavplugin::CommandPlugin::set_home_srv
std::map< std::string,
ParamSetOpt * > 
mavplugin::ParamPlugin::set_parameters
ros::ServiceServer mavplugin::ParamPlugin::set_srv
ros::Subscriber mavplugin::SetpointPositionPlugin::setpoint_sub
ros::Timer mavplugin::WaypointPlugin::shedule_timer
ros::Timer mavplugin::ParamPlugin::shedule_timer
 for startup shedule fetch
uint8_t mavplugin::FTPRequest::PayloadHeader::size
 Size of data.
ros::NodeHandle mavplugin::SetpointVelocityPlugin::sp_nh
ros::NodeHandle mavplugin::SetpointAccelerationPlugin::sp_nh
ros::NodeHandle mavplugin::SetpointPositionPlugin::sp_nh
ros::NodeHandle mavplugin::SetpointAttitudePlugin::sp_nh
ros::Publisher mavplugin::SystemStatusPlugin::state_pub
ros::Publisher mavplugin::TDRRadioPlugin::status_pub
SystemStatusDiag mavplugin::SystemStatusPlugin::sys_diag
ros::Timer mavplugin::SystemTimePlugin::sys_time_timer
ros::ServiceServer mavplugin::CommandPlugin::takeoff_srv
TDRRadioStatus mavplugin::TDRRadioPlugin::tdr_diag
ros::Publisher mavplugin::IMUPubPlugin::temp_pub
tf::TransformBroadcaster mavplugin::LocalPositionPlugin::tf_broadcaster
tf::TransformBroadcaster mavplugin::GlobalPositionPlugin::tf_broadcaster
double mavplugin::SetpointPositionPlugin::tf_rate
double mavplugin::SetpointAttitudePlugin::tf_rate
std::thread mavplugin::TFListenerMixin< D >::tf_thread
boost::function< void(const
tf::Transform &, const
ros::Time &)> 
mavplugin::TFListenerMixin< D >::tf_transform_cb
std::string mavplugin::TFListenerMixin< D >::thd_name
ros::Subscriber mavplugin::SetpointAttitudePlugin::throttle_sub
ros::Publisher mavplugin::SystemTimePlugin::time_offset_pub
uint64_t mavplugin::SystemTimePlugin::time_offset_us
ros::Publisher mavplugin::GPSPlugin::time_ref_pub
ros::Publisher mavplugin::SystemTimePlugin::time_ref_pub
std::string mavplugin::GPSPlugin::time_ref_source
std::string mavplugin::SystemTimePlugin::time_ref_source
ros::Timer mavplugin::ParamPlugin::timeout_timer
 for timeout resend
ros::Timer mavplugin::SystemStatusPlugin::timeout_timer
std::vector< ros::Timemavplugin::HeartbeatStatus::times_
std::vector< ros::Timemavplugin::TimeSyncStatus::times_
const double mavplugin::HeartbeatStatus::tolerance_
const double mavplugin::TimeSyncStatus::tolerance_
ros::ServiceServer mavplugin::FTPPlugin::truncate_srv
UAS * mavplugin::SetpointVelocityPlugin::uas
UAS * mavplugin::SetpointAccelerationPlugin::uas
UAS * mavplugin::LocalPositionPlugin::uas
UAS * mavplugin::RCIOPlugin::uas
UAS * mavplugin::SetpointPositionPlugin::uas
UAS * mavplugin::GlobalPositionPlugin::uas
UAS * mavplugin::CommandPlugin::uas
UAS * mavplugin::SafetyAreaPlugin::uas
UAS * mavplugin::IMUPubPlugin::uas
UAS * mavplugin::SetpointAttitudePlugin::uas
UAS * mavplugin::GPSPlugin::uas
UAS * mavplugin::SystemTimePlugin::uas
UAS * mavplugin::WaypointPlugin::uas
UAS * mavplugin::ParamPlugin::uas
UAS * mavplugin::SystemStatusPlugin::uas
boost::array< double, 9 > mavplugin::IMUPubPlugin::unk_orientation_cov
float mavplugin::HwStatus::vcc
ros::Publisher mavplugin::GlobalPositionPlugin::vel_pub
ros::Publisher mavplugin::GPSPlugin::vel_pub
ros::Subscriber mavplugin::SetpointVelocityPlugin::vel_sub
ros::Publisher mavplugin::VfrHudPlugin::vfr_pub
float mavplugin::BatteryStatusDiag::voltage
std::vector< WaypointItem > mavplugin::WaypointPlugin::waypoints
ros::Publisher mavplugin::VfrHudPlugin::wind_pub
const size_t mavplugin::HeartbeatStatus::window_size_
const size_t mavplugin::TimeSyncStatus::window_size_
size_t mavplugin::WaypointPlugin::wp_count
size_t mavplugin::WaypointPlugin::wp_cur_active
size_t mavplugin::WaypointPlugin::wp_cur_id
ros::Publisher mavplugin::WaypointPlugin::wp_list_pub
ros::NodeHandle mavplugin::WaypointPlugin::wp_nh
size_t mavplugin::WaypointPlugin::wp_retries
size_t mavplugin::WaypointPlugin::wp_set_active
enum
mavplugin::WaypointPlugin:: { ... }  
mavplugin::WaypointPlugin::wp_state
const ros::Duration mavplugin::WaypointPlugin::WP_TIMEOUT_DT
static constexpr int mavplugin::WaypointPlugin::WP_TIMEOUT_MS = 1000
 Timeout for pull/push operations.
ros::Timer mavplugin::WaypointPlugin::wp_timer
V_FileData mavplugin::FTPPlugin::write_buffer
V_FileData::iterator mavplugin::FTPPlugin::write_it
uint32_t mavplugin::FTPPlugin::write_offset
ros::ServiceServer mavplugin::FTPPlugin::write_srv
double mavplugin::WaypointItem::x_lat
double mavplugin::WaypointItem::y_long
double mavplugin::WaypointItem::z_alt

Friends

class mavplugin::SetpointVelocityPlugin::SetPositionTargetLocalNEDMixin
class mavplugin::SetpointAccelerationPlugin::SetPositionTargetLocalNEDMixin
class mavplugin::SetpointPositionPlugin::SetPositionTargetLocalNEDMixin
class mavplugin::SetpointPositionPlugin::TFListenerMixin
class mavplugin::SetpointAttitudePlugin::TFListenerMixin

Detailed Description

MAVROS Plugin system.


Define Documentation

#define MESSAGE_HANDLER (   _message_id,
  _class_method_ptr 
)    { _message_id, boost::bind(_class_method_ptr, this, _1, _2, _3) }

Helper macros to define message handler map item.

Examples:
dummy.cpp.

Definition at line 43 of file mavros_plugin.h.

#define SERVICE_IDLE_CHECK ( )
Value:
if (op_state != OP_IDLE) {                      \
                ROS_ERROR_NAMED("ftp", "FTP: Busy");    \
                return false;                           \
        }

Service handler common header code.

Definition at line 876 of file ftp.cpp.


Typedef Documentation

typedef boost::shared_ptr<MavRosPlugin const> mavplugin::MavRosPlugin::ConstPtr

Definition at line 60 of file mavros_plugin.h.

typedef std::lock_guard<std::recursive_mutex> mavplugin::lock_guard

Definition at line 37 of file mavros_plugin.h.

typedef boost::function<void(const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) mavplugin::MavRosPlugin::message_handler)

Definition at line 56 of file mavros_plugin.h.

typedef std::map<uint8_t, message_handler> mavplugin::MavRosPlugin::message_map
Examples:
dummy.cpp.

Definition at line 57 of file mavros_plugin.h.

typedef boost::any mavplugin::Parameter::param_t

Definition at line 47 of file param.cpp.

typedef boost::shared_ptr<MavRosPlugin> mavplugin::MavRosPlugin::Ptr

Definition at line 59 of file mavros_plugin.h.

typedef std::unique_lock<std::recursive_mutex> mavplugin::unique_lock

Definition at line 38 of file mavros_plugin.h.

typedef std::vector<uint8_t> mavplugin::FTPPlugin::V_FileData

This type used in servicies to store 'data' fileds.

Definition at line 270 of file ftp.cpp.


Enumeration Type Documentation

anonymous enum [private]
Enumerator:
PR_IDLE 
PR_RXLIST 
PR_RXPARAM 
PR_TXPARAM 

Definition at line 411 of file param.cpp.

anonymous enum [private]
Enumerator:
WP_IDLE 
WP_RXLIST 
WP_RXWP 
WP_TXLIST 
WP_TXWP 
WP_CLEAR 
WP_SET_CUR 

Definition at line 222 of file waypoint.cpp.

Error codes returned in Nak response.

Enumerator:
kErrNone 
kErrFail 

Unknown failure.

kErrFailErrno 

Command failed, errno sent back in PayloadHeader.data[1].

kErrInvalidDataSize 

PayloadHeader.size is invalid.

kErrInvalidSession 

Session is not currently open.

kErrNoSessionsAvailable 

All available Sessions in use.

kErrEOF 

Offset past end of file for List and Read commands.

kErrUnknownCommand 

Unknown command opcode.

Definition at line 95 of file ftp.cpp.

Command opcodes.

Enumerator:
kCmdNone 

ignored, always acked

kCmdTerminateSession 

Terminates open Read session.

kCmdResetSessions 

Terminates all open Read sessions.

kCmdListDirectory 

List files in <path> from <offset>

kCmdOpenFileRO 

Opens file at <path> for reading, returns <session>

kCmdReadFile 

Reads <size> bytes from <offset> in <session>

kCmdCreateFile 

Creates file at <path> for writing, returns <session>

kCmdWriteFile 

Writes <size> bytes to <offset> in <session>

kCmdRemoveFile 

Remove file at <path>

kCmdCreateDirectory 

Creates directory at <path>

kCmdRemoveDirectory 

Removes Directory at <path>, must be empty.

kCmdOpenFileWO 

Opens file at <path> for writing, returns <session>

kCmdTruncateFile 

Truncate file at <path> to <offset> length.

kCmdRename 

Rename <path1> to <path2>

kCmdCalcFileCRC32 

Calculate CRC32 for file at <path>

kRspAck 

Ack response.

kRspNak 

Nak response.

Definition at line 73 of file ftp.cpp.

Enumerator:
OP_IDLE 
OP_ACK 
OP_LIST 
OP_OPEN 
OP_READ 
OP_WRITE 
OP_CHECKSUM 

Definition at line 272 of file ftp.cpp.


Function Documentation

Definition at line 108 of file setpoint_accel.cpp.

void mavplugin::FTPPlugin::add_dirent ( const char *  ptr,
size_t  slen 
) [inline]

Definition at line 684 of file ftp.cpp.

bool mavplugin::CommandPlugin::arming_cb ( mavros::CommandBool::Request &  req,
mavros::CommandBool::Response &  res 
) [inline, private]

Definition at line 285 of file command.cpp.

mavplugin::BatteryStatusDiag::BatteryStatusDiag ( const std::string  name) [inline]

Definition at line 202 of file sys_status.cpp.

static bool mavplugin::Parameter::check_exclude_param_id ( std::string  param_id) [inline, static]

Exclude this parameters from ~param/push

Definition at line 306 of file param.cpp.

bool mavplugin::FTPPlugin::checksum_cb ( mavros::FileChecksum::Request &  req,
mavros::FileChecksum::Response &  res 
) [inline]

Definition at line 1022 of file ftp.cpp.

void mavplugin::FTPPlugin::checksum_crc32_file ( std::string &  path) [inline]

Definition at line 839 of file ftp.cpp.

Definition at line 57 of file sys_time.cpp.

bool mavplugin::WaypointPlugin::clear_cb ( mavros::WaypointClear::Request &  req,
mavros::WaypointClear::Response &  res 
) [inline, private]

Definition at line 778 of file waypoint.cpp.

bool mavplugin::FTPPlugin::close_cb ( mavros::FileClose::Request &  req,
mavros::FileClose::Response &  res 
) [inline]

Definition at line 919 of file ftp.cpp.

bool mavplugin::FTPPlugin::close_file ( std::string &  path) [inline]

Definition at line 749 of file ftp.cpp.

void mavplugin::CommandPlugin::command_int ( 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 
) [inline, private]

Definition at line 242 of file command.cpp.

bool mavplugin::CommandPlugin::command_int_cb ( mavros::CommandInt::Request &  req,
mavros::CommandInt::Response &  res 
) [inline, private]

Definition at line 275 of file command.cpp.

void mavplugin::CommandPlugin::command_long ( uint16_t  command,
uint8_t  confirmation,
float  param1,
float  param2,
float  param3,
float  param4,
float  param5,
float  param6,
float  param7 
) [inline, private]

Definition at line 224 of file command.cpp.

bool mavplugin::CommandPlugin::command_long_cb ( mavros::CommandLong::Request &  req,
mavros::CommandLong::Response &  res 
) [inline, private]

Definition at line 264 of file command.cpp.

Definition at line 61 of file command.cpp.

mavplugin::CommandTransaction::CommandTransaction ( uint16_t  command) [inline, explicit]

Definition at line 47 of file command.cpp.

static constexpr int mavplugin::FTPPlugin::compute_rw_timeout ( size_t  len) [inline, static]

Definition at line 845 of file ftp.cpp.

void mavplugin::RCIOPlugin::connection_cb ( bool  connected) [inline, private]

Definition at line 222 of file rc_io.cpp.

void mavplugin::WaypointPlugin::connection_cb ( bool  connected) [inline, private]

Definition at line 520 of file waypoint.cpp.

void mavplugin::ParamPlugin::connection_cb ( bool  connected) [inline, private]

Definition at line 580 of file param.cpp.

void mavplugin::FTPPlugin::create_directory ( std::string &  path) [inline]

Definition at line 829 of file ftp.cpp.

uint8_t* mavplugin::FTPRequest::data ( ) [inline]

Definition at line 119 of file ftp.cpp.

char* mavplugin::FTPRequest::data_c ( ) [inline]

Definition at line 123 of file ftp.cpp.

uint32_t* mavplugin::FTPRequest::data_u32 ( ) [inline]

Definition at line 127 of file ftp.cpp.

bool mavplugin::FTPRequest::decode ( UAS uas,
const mavlink_message_t msg 
) [inline]

Decode and check target system.

Definition at line 153 of file ftp.cpp.

Examples:
dummy.cpp.

Definition at line 40 of file dummy.cpp.

void mavplugin::IMUPubPlugin::fill_imu_msg_attitude ( sensor_msgs::ImuPtr &  imu_msg,
tf::Quaternion orientation,
double  xg,
double  yg,
double  zg 
) [inline, private]

fill imu/data message

Definition at line 147 of file imu_pub.cpp.

void mavplugin::IMUPubPlugin::fill_imu_msg_raw ( sensor_msgs::ImuPtr &  imu_msg,
double  xg,
double  yg,
double  zg,
double  xa,
double  ya,
double  za 
) [inline, private]

fill imu/data_raw message, store linear acceleration for imu/data

Definition at line 166 of file imu_pub.cpp.

static WaypointItem mavplugin::WaypointItem::from_mission_item ( mavlink_mission_item_t &  mit) [inline, static]

Definition at line 93 of file waypoint.cpp.

static WaypointItem mavplugin::WaypointItem::from_msg ( mavros::Waypoint &  wp,
uint16_t  seq 
) [inline, static]

Definition at line 74 of file waypoint.cpp.

static param_t mavplugin::Parameter::from_param_value ( mavlink_param_value_t &  pmsg) [inline, static]

Convert mavlink_param_value_t to internal format

Definition at line 57 of file param.cpp.

Parameter::param_t mavplugin::ParamPlugin::from_param_value ( mavlink_param_value_t &  msg) [inline, private]

Definition at line 423 of file param.cpp.

static param_t mavplugin::Parameter::from_param_value_apm_quirk ( mavlink_param_value_t &  pmsg) [inline, static]

Variation of Parameter::from_param_value with quirks for ArduPilotMega

Definition at line 92 of file param.cpp.

static param_t mavplugin::Parameter::from_xmlrpc_value ( XmlRpc::XmlRpcValue xml) [inline, static]

Convert rosparam to internal value

Definition at line 288 of file param.cpp.

Definition at line 208 of file ftp.cpp.

Definition at line 187 of file ftp.cpp.

bool mavplugin::ParamPlugin::get_cb ( mavros::ParamGet::Request &  req,
mavros::ParamGet::Response &  res 
) [inline, private]

get parameter ~param/get

Definition at line 891 of file param.cpp.

std::string const mavplugin::DummyPlugin::get_name ( ) const [inline, virtual]

Returns plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Examples:
dummy.cpp.

Definition at line 57 of file dummy.cpp.

std::string const mavplugin::VfrHudPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 58 of file vfr_hud.cpp.

const std::string mavplugin::SetpointVelocityPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 59 of file setpoint_velocity.cpp.

std::string const mavplugin::RCIOPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 62 of file rc_io.cpp.

const std::string mavplugin::SetpointAccelerationPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 62 of file setpoint_accel.cpp.

std::string const mavplugin::LocalPositionPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 63 of file local_position.cpp.

const std::string mavplugin::SetpointPositionPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 73 of file setpoint_position.cpp.

virtual const std::string mavplugin::MavRosPlugin::get_name ( ) const [pure virtual]
std::string const mavplugin::GlobalPositionPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 79 of file global_position.cpp.

std::string const mavplugin::IMUPubPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 80 of file imu_pub.cpp.

std::string const mavplugin::CommandPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 82 of file command.cpp.

const std::string mavplugin::SafetyAreaPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 84 of file safety_area.cpp.

const std::string mavplugin::SetpointAttitudePlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 94 of file setpoint_attitude.cpp.

std::string const mavplugin::TDRRadioPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 115 of file 3dr_radio.cpp.

std::string const mavplugin::GPSPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 123 of file gps.cpp.

std::string const mavplugin::SystemTimePlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 169 of file sys_time.cpp.

std::string const mavplugin::WaypointPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 193 of file waypoint.cpp.

std::string const mavplugin::ParamPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 375 of file param.cpp.

const std::string mavplugin::SystemStatusPlugin::get_name ( ) const [inline, virtual]

Plugin name (CamelCase)

Implements mavplugin::MavRosPlugin.

Definition at line 389 of file sys_status.cpp.

const message_map mavplugin::VfrHudPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 62 of file vfr_hud.cpp.

const message_map mavplugin::SetpointVelocityPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 63 of file setpoint_velocity.cpp.

const message_map mavplugin::DummyPlugin::get_rx_handlers ( ) [inline, virtual]

This function returns message<->handler mapping

Each entry defined by MESSAGE_HANDLER() macro

Implements mavplugin::MavRosPlugin.

Examples:
dummy.cpp.

Definition at line 66 of file dummy.cpp.

const message_map mavplugin::RCIOPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 66 of file rc_io.cpp.

const message_map mavplugin::SetpointAccelerationPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 66 of file setpoint_accel.cpp.

const message_map mavplugin::LocalPositionPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 67 of file local_position.cpp.

const message_map mavplugin::SetpointPositionPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 77 of file setpoint_position.cpp.

virtual const message_map mavplugin::MavRosPlugin::get_rx_handlers ( ) [pure virtual]
const message_map mavplugin::GlobalPositionPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 83 of file global_position.cpp.

const message_map mavplugin::IMUPubPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 84 of file imu_pub.cpp.

const message_map mavplugin::CommandPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 86 of file command.cpp.

const message_map mavplugin::SafetyAreaPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Todo:
Publish SAFETY_ALLOWED_AREA message

Implements mavplugin::MavRosPlugin.

Definition at line 88 of file safety_area.cpp.

const message_map mavplugin::SetpointAttitudePlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 98 of file setpoint_attitude.cpp.

const message_map mavplugin::TDRRadioPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 119 of file 3dr_radio.cpp.

const message_map mavplugin::GPSPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 127 of file gps.cpp.

const message_map mavplugin::SystemTimePlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 173 of file sys_time.cpp.

const message_map mavplugin::WaypointPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 197 of file waypoint.cpp.

const message_map mavplugin::ParamPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 379 of file param.cpp.

const message_map mavplugin::SystemStatusPlugin::get_rx_handlers ( ) [inline, virtual]

Return map with message rx handlers.

Implements mavplugin::MavRosPlugin.

Definition at line 393 of file sys_status.cpp.

Definition at line 146 of file ftp.cpp.

Definition at line 53 of file global_position.cpp.

void mavplugin::WaypointPlugin::go_idle ( void  ) [inline, private]

Definition at line 553 of file waypoint.cpp.

void mavplugin::FTPPlugin::go_idle ( bool  is_error_,
int  r_errno_ = 0 
) [inline]

Go to IDLE mode.

Parameters:
is_error_mark that caused in error case
r_errno_set r_errno in error case

Definition at line 572 of file ftp.cpp.

void mavplugin::ParamPlugin::go_idle ( void  ) [inline, private]

Definition at line 688 of file param.cpp.

bool mavplugin::WaypointPlugin::goto_cb ( mavros::WaypointGOTO::Request &  req,
mavros::WaypointGOTO::Response &  res 
) [inline, private]

Definition at line 817 of file waypoint.cpp.

mavplugin::GPSInfo::GPSInfo ( const std::string  name) [inline, explicit]

Definition at line 41 of file gps.cpp.

Definition at line 102 of file gps.cpp.

bool mavplugin::CommandPlugin::guided_cb ( mavros::CommandBool::Request &  req,
mavros::CommandBool::Response &  res 
) [inline, private]

Definition at line 324 of file command.cpp.

Definition at line 553 of file ftp.cpp.

Definition at line 412 of file ftp.cpp.

Definition at line 470 of file ftp.cpp.

Definition at line 483 of file ftp.cpp.

Definition at line 516 of file ftp.cpp.

void mavplugin::IMUPubPlugin::handle_attitude ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 186 of file imu_pub.cpp.

void mavplugin::IMUPubPlugin::handle_attitude_quaternion ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 215 of file imu_pub.cpp.

void mavplugin::CommandPlugin::handle_command_ack ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 112 of file command.cpp.

void mavplugin::FTPPlugin::handle_file_transfer_protocol ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline]
Todo:

exchange speed calculation

diagnostics

Definition at line 329 of file ftp.cpp.

void mavplugin::GlobalPositionPlugin::handle_global_position_int ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]
Todo:
Handler for GLOBAL_POSITION_INT_COV

Adapted from gps_umd ROS package http://wiki.ros.org/gps_umd Author: Ken Tossell <ken at="" tossell="" dot="" net>="">

Definition at line 110 of file global_position.cpp.

void mavplugin::GPSPlugin::handle_gps_raw_int ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 145 of file gps.cpp.

void mavplugin::GPSPlugin::handle_gps_status ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 212 of file gps.cpp.

void mavplugin::DummyPlugin::handle_heartbeat ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]
Examples:
dummy.cpp.

Definition at line 75 of file dummy.cpp.

void mavplugin::SystemStatusPlugin::handle_heartbeat ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 486 of file sys_status.cpp.

void mavplugin::IMUPubPlugin::handle_highres_imu ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 242 of file imu_pub.cpp.

void mavplugin::LocalPositionPlugin::handle_local_position_ned ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 84 of file local_position.cpp.

template<typename msgT >
void mavplugin::TDRRadioPlugin::handle_message ( msgT &  rst,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 156 of file 3dr_radio.cpp.

void mavplugin::WaypointPlugin::handle_mission_ack ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 404 of file waypoint.cpp.

void mavplugin::WaypointPlugin::handle_mission_count ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 359 of file waypoint.cpp.

void mavplugin::WaypointPlugin::handle_mission_current ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 332 of file waypoint.cpp.

void mavplugin::WaypointPlugin::handle_mission_item ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 261 of file waypoint.cpp.

void mavplugin::WaypointPlugin::handle_mission_item_reached ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 396 of file waypoint.cpp.

void mavplugin::WaypointPlugin::handle_mission_request ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 307 of file waypoint.cpp.

void mavplugin::ParamPlugin::handle_param_value ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 439 of file param.cpp.

void mavplugin::TDRRadioPlugin::handle_radio_status ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 136 of file 3dr_radio.cpp.

void mavplugin::IMUPubPlugin::handle_raw_imu ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 296 of file imu_pub.cpp.

void mavplugin::RCIOPlugin::handle_rc_channels ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 123 of file rc_io.cpp.

void mavplugin::RCIOPlugin::handle_rc_channels_raw ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 89 of file rc_io.cpp.

Definition at line 359 of file ftp.cpp.

Definition at line 374 of file ftp.cpp.

void mavplugin::IMUPubPlugin::handle_scaled_imu ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 341 of file imu_pub.cpp.

void mavplugin::IMUPubPlugin::handle_scaled_pressure ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 381 of file imu_pub.cpp.

void mavplugin::RCIOPlugin::handle_servo_output_raw ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 172 of file rc_io.cpp.

void mavplugin::DummyPlugin::handle_statustext ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]
Examples:
dummy.cpp.

Definition at line 85 of file dummy.cpp.

void mavplugin::SystemStatusPlugin::handle_statustext ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 525 of file sys_status.cpp.

void mavplugin::DummyPlugin::handle_sys_status ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]
Examples:
dummy.cpp.

Definition at line 80 of file dummy.cpp.

void mavplugin::SystemStatusPlugin::handle_sys_status ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 506 of file sys_status.cpp.

void mavplugin::SystemTimePlugin::handle_system_time ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 190 of file sys_time.cpp.

void mavplugin::VfrHudPlugin::handle_vfr_hud ( const mavlink_message_t msg,
uint8_t  sysid,
uint8_t  compid 
) [inline, private]

Definition at line 75 of file vfr_hud.cpp.

PayloadHeader* mavplugin::FTPRequest::header ( ) [inline]

Definition at line 115 of file ftp.cpp.

void mavplugin::SystemStatusPlugin::heartbeat_cb ( const ros::TimerEvent event) [inline, private]

Definition at line 560 of file sys_status.cpp.

mavplugin::HeartbeatStatus::HeartbeatStatus ( const std::string  name,
size_t  win_size 
) [inline]

Definition at line 45 of file sys_status.cpp.

mavplugin::HwStatus::HwStatus ( const std::string  name) [inline]

Definition at line 285 of file sys_status.cpp.

Definition at line 45 of file imu_pub.cpp.

void mavplugin::SafetyAreaPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 46 of file safety_area.cpp.

void mavplugin::VfrHudPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer. Constructor should not do this.

Implements mavplugin::MavRosPlugin.

Definition at line 47 of file vfr_hud.cpp.

void mavplugin::DummyPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer. Constructor should not do this.

Implements mavplugin::MavRosPlugin.

Examples:
dummy.cpp.

Definition at line 47 of file dummy.cpp.

void mavplugin::LocalPositionPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 48 of file local_position.cpp.

void mavplugin::RCIOPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 48 of file rc_io.cpp.

void mavplugin::SetpointVelocityPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 48 of file setpoint_velocity.cpp.

void mavplugin::SetpointPositionPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 49 of file setpoint_position.cpp.

void mavplugin::SetpointAccelerationPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 50 of file setpoint_accel.cpp.

void mavplugin::SetpointAttitudePlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 53 of file setpoint_attitude.cpp.

void mavplugin::IMUPubPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 53 of file imu_pub.cpp.

void mavplugin::GlobalPositionPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 59 of file global_position.cpp.

void mavplugin::CommandPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 66 of file command.cpp.

virtual void mavplugin::MavRosPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [pure virtual]
void mavplugin::TDRRadioPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 107 of file 3dr_radio.cpp.

void mavplugin::GPSPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 107 of file gps.cpp.

void mavplugin::SystemTimePlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 143 of file sys_time.cpp.

void mavplugin::WaypointPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 168 of file waypoint.cpp.

void mavplugin::SystemStatusPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 340 of file sys_status.cpp.

void mavplugin::ParamPlugin::initialize ( UAS uas,
ros::NodeHandle nh,
diagnostic_updater::Updater diag_updater 
) [inline, virtual]

Plugin initializer.

Parameters:
[in]uasUAS instance (handles FCU connection and some statuses)
[in]nhmain mavros ros::NodeHandle (private)
[in]diag_updatermain diagnostic updater

Implements mavplugin::MavRosPlugin.

Definition at line 356 of file param.cpp.

bool mavplugin::SetpointAttitudePlugin::is_normalized ( float  throttle,
const float  min,
const float  max 
) [inline, private]

Definition at line 214 of file setpoint_attitude.cpp.

bool mavplugin::CommandPlugin::land_cb ( mavros::CommandTOL::Request &  req,
mavros::CommandTOL::Response &  res 
) [inline, private]

Definition at line 314 of file command.cpp.

bool mavplugin::FTPPlugin::list_cb ( mavros::FileList::Request &  req,
mavros::FileList::Response &  res 
) [inline]

Definition at line 882 of file ftp.cpp.

void mavplugin::FTPPlugin::list_directory ( std::string &  path) [inline]

Definition at line 719 of file ftp.cpp.

Definition at line 714 of file ftp.cpp.

Definition at line 43 of file local_position.cpp.

mavplugin::MavRosPlugin::MavRosPlugin ( ) [inline, protected]

Plugin constructor Should not do anything before initialize()

Definition at line 90 of file mavros_plugin.h.

mavplugin::MemInfo::MemInfo ( const std::string  name) [inline]

Definition at line 249 of file sys_status.cpp.

void mavplugin::WaypointPlugin::mission_ack ( enum MAV_MISSION_RESULT  type) [inline, private]

Definition at line 710 of file waypoint.cpp.

Definition at line 700 of file waypoint.cpp.

void mavplugin::WaypointPlugin::mission_count ( uint16_t  cnt) [inline, private]

Definition at line 689 of file waypoint.cpp.

void mavplugin::WaypointPlugin::mission_item ( WaypointItem wp) [inline, private]

Definition at line 636 of file waypoint.cpp.

void mavplugin::WaypointPlugin::mission_request ( uint16_t  seq) [inline, private]

Definition at line 657 of file waypoint.cpp.

Definition at line 679 of file waypoint.cpp.

void mavplugin::WaypointPlugin::mission_set_current ( uint16_t  seq) [inline, private]

Definition at line 668 of file waypoint.cpp.

bool mavplugin::FTPPlugin::mkdir_cb ( mavros::FileMakeDir::Request &  req,
mavros::FileMakeDir::Response &  res 
) [inline]

Definition at line 1000 of file ftp.cpp.

bool mavplugin::FTPPlugin::open_cb ( mavros::FileOpen::Request &  req,
mavros::FileOpen::Response &  res 
) [inline]

Definition at line 897 of file ftp.cpp.

bool mavplugin::FTPPlugin::open_file ( std::string &  path,
int  mode 
) [inline]

Definition at line 728 of file ftp.cpp.

Definition at line 229 of file rc_io.cpp.

void mavplugin::ParamPlugin::param_request_list ( ) [inline, private]

Definition at line 526 of file param.cpp.

void mavplugin::ParamPlugin::param_request_read ( std::string  id,
int16_t  index = -1 
) [inline, private]

Definition at line 536 of file param.cpp.

void mavplugin::ParamPlugin::param_set ( Parameter param) [inline, private]

Definition at line 559 of file param.cpp.

Definition at line 345 of file param.cpp.

mavplugin::ParamSetOpt::ParamSetOpt ( Parameter _p,
size_t  _rem 
) [inline]

Definition at line 326 of file param.cpp.

Definition at line 200 of file setpoint_attitude.cpp.

Definition at line 194 of file setpoint_attitude.cpp.

void mavplugin::SystemStatusPlugin::process_statustext_apm_quirk ( uint8_t  severity,
std::string &  text 
) [inline, private]

Send STATUSTEXT messate to rosout with APM severity levels

Parameters:
[in]severityAPM levels.

Definition at line 460 of file sys_status.cpp.

void mavplugin::SystemStatusPlugin::process_statustext_normal ( uint8_t  severity,
std::string &  text 
) [inline, private]

Sent STATUSTEXT message to rosout

Parameters:
[in]severityLevels defined in common.xml

Definition at line 429 of file sys_status.cpp.

Definition at line 618 of file waypoint.cpp.

bool mavplugin::WaypointPlugin::pull_cb ( mavros::WaypointPull::Request &  req,
mavros::WaypointPull::Response &  res 
) [inline, private]

Definition at line 723 of file waypoint.cpp.

bool mavplugin::ParamPlugin::pull_cb ( mavros::ParamPull::Request &  req,
mavros::ParamPull::Response &  res 
) [inline, private]

fetches all parameters from device ~param/pull

Definition at line 743 of file param.cpp.

bool mavplugin::WaypointPlugin::push_cb ( mavros::WaypointPush::Request &  req,
mavros::WaypointPush::Response &  res 
) [inline, private]

Definition at line 745 of file waypoint.cpp.

bool mavplugin::ParamPlugin::push_cb ( mavros::ParamPush::Request &  req,
mavros::ParamPush::Response &  res 
) [inline, private]

push all parameter value to device ~param/push

Definition at line 795 of file param.cpp.

uint8_t* mavplugin::FTPRequest::raw_payload ( ) [inline]

Definition at line 111 of file ftp.cpp.

void mavplugin::RCIOPlugin::rc_channels_override ( const boost::array< uint16_t, 8 > &  channels) [inline, private]

Definition at line 203 of file rc_io.cpp.

Definition at line 41 of file rc_io.cpp.

bool mavplugin::FTPPlugin::read_cb ( mavros::FileRead::Request &  req,
mavros::FileRead::Response &  res 
) [inline]

Definition at line 932 of file ftp.cpp.

bool mavplugin::FTPPlugin::read_file ( std::string &  path,
size_t  off,
size_t  len 
) [inline]

Definition at line 768 of file ftp.cpp.

Definition at line 763 of file ftp.cpp.

bool mavplugin::FTPPlugin::remove_cb ( mavros::FileRemove::Request &  req,
mavros::FileRemove::Response &  res 
) [inline]

Definition at line 963 of file ftp.cpp.

void mavplugin::FTPPlugin::remove_directory ( std::string &  path) [inline]

Definition at line 834 of file ftp.cpp.

void mavplugin::FTPPlugin::remove_file ( std::string &  path) [inline]

Definition at line 814 of file ftp.cpp.

bool mavplugin::FTPPlugin::rename_ ( std::string &  old_path,
std::string &  new_path 
) [inline]

Definition at line 819 of file ftp.cpp.

bool mavplugin::FTPPlugin::rename_cb ( mavros::FileRename::Request &  req,
mavros::FileRename::Response &  res 
) [inline]

Definition at line 974 of file ftp.cpp.

void mavplugin::WaypointPlugin::request_mission_done ( void  ) [inline, private]

Definition at line 544 of file waypoint.cpp.

bool mavplugin::FTPPlugin::reset_cb ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [inline]

Reset communication on both sides.

Note:
This call break other calls, so use carefully.

Definition at line 1040 of file ftp.cpp.

void mavplugin::WaypointPlugin::restart_timeout_timer ( void  ) [inline, private]

Definition at line 559 of file waypoint.cpp.

void mavplugin::ParamPlugin::restart_timeout_timer ( void  ) [inline, private]

Definition at line 682 of file param.cpp.

void mavplugin::WaypointPlugin::restart_timeout_timer_int ( void  ) [inline, private]

Definition at line 564 of file waypoint.cpp.

bool mavplugin::FTPPlugin::rmdir_cb ( mavros::FileRemoveDir::Request &  req,
mavros::FileRemoveDir::Response &  res 
) [inline]

Definition at line 1011 of file ftp.cpp.

Implements diagnostic_updater::DiagnosticTask.

Definition at line 56 of file gps.cpp.

Implements diagnostic_updater::DiagnosticTask.

Definition at line 85 of file sys_time.cpp.

Implements diagnostic_updater::DiagnosticTask.

Definition at line 140 of file sys_status.cpp.

Implements diagnostic_updater::DiagnosticTask.

Definition at line 222 of file sys_status.cpp.

Implements diagnostic_updater::DiagnosticTask.

Definition at line 261 of file sys_status.cpp.

Implements diagnostic_updater::DiagnosticTask.

Definition at line 298 of file sys_status.cpp.

void mavplugin::SafetyAreaPlugin::safety_set_allowed_area ( uint8_t  coordinate_frame,
float  p1x,
float  p1y,
float  p1z,
float  p2x,
float  p2y,
float  p2z 
) [inline, private]

Definition at line 103 of file safety_area.cpp.

Definition at line 139 of file safety_area.cpp.

Definition at line 42 of file safety_area.cpp.

void mavplugin::FTPRequest::send ( UAS uas,
uint16_t  seqNumber 
) [inline]

Encode and send message.

Definition at line 168 of file ftp.cpp.

void mavplugin::FTPPlugin::send_any_path_command ( FTPRequest::Opcode  op,
const std::string  debug_msg,
std::string &  path,
uint32_t  offset 
) [inline]

Send any command with string payload (usually file/dir path)

Definition at line 594 of file ftp.cpp.

void mavplugin::SetpointAttitudePlugin::send_attitude_ang_velocity ( const ros::Time stamp,
const float  vx,
const float  vy,
const float  vz 
) [inline, private]

Send angular velocity setpoint to FCU attitude controller

ENU frame.

Definition at line 165 of file setpoint_attitude.cpp.

void mavplugin::SetpointAttitudePlugin::send_attitude_throttle ( const float  throttle) [inline, private]

Send throttle to FCU attitude controller

Definition at line 180 of file setpoint_attitude.cpp.

void mavplugin::SetpointAttitudePlugin::send_attitude_transform ( const tf::Transform transform,
const ros::Time stamp 
) [inline, private]

Send attitude setpoint to FCU attitude controller

ENU frame.

Definition at line 141 of file setpoint_attitude.cpp.

void mavplugin::FTPPlugin::send_calc_file_crc32_command ( std::string &  path) [inline]

Definition at line 678 of file ftp.cpp.

bool mavplugin::CommandPlugin::send_command_int ( 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 
) [inline, private]

Common function for COMMAND_INT service callbacks.

Definition at line 202 of file command.cpp.

bool mavplugin::CommandPlugin::send_command_long_and_wait ( 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 
) [inline, private]

Common function for command service callbacks.

NOTE: success is bool in messages, but has unsigned char type in C++

Note:
APM always send COMMAND_ACK, while PX4 never.

Definition at line 143 of file command.cpp.

Definition at line 614 of file ftp.cpp.

void mavplugin::FTPPlugin::send_create_dir_command ( std::string &  path) [inline]

Definition at line 670 of file ftp.cpp.

Definition at line 602 of file ftp.cpp.

Definition at line 606 of file ftp.cpp.

Definition at line 610 of file ftp.cpp.

bool mavplugin::ParamPlugin::send_param_set_and_wait ( Parameter param) [inline, private]

Definition at line 709 of file param.cpp.

Definition at line 626 of file ftp.cpp.

void mavplugin::FTPPlugin::send_remove_command ( std::string &  path) [inline]

Definition at line 645 of file ftp.cpp.

void mavplugin::FTPPlugin::send_remove_dir_command ( std::string &  path) [inline]

Definition at line 674 of file ftp.cpp.

bool mavplugin::FTPPlugin::send_rename_command ( std::string &  old_path,
std::string &  new_path 
) [inline]

Definition at line 649 of file ftp.cpp.

Definition at line 580 of file ftp.cpp.

void mavplugin::SafetyAreaPlugin::send_safety_set_allowed_area ( float  p1x,
float  p1y,
float  p1z,
float  p2x,
float  p2y,
float  p2z 
) [inline, private]

Send a safety zone (volume), which is defined by two corners of a cube, to the FCU.

Note:
ENU frame.

Definition at line 124 of file safety_area.cpp.

void mavplugin::SetpointAccelerationPlugin::send_setpoint_acceleration ( const ros::Time stamp,
float  afx,
float  afy,
float  afz 
) [inline, private]

Send acceleration/force to FCU acceleration controller

Note: send only AFX AFY AFZ. ENU frame.

Definition at line 86 of file setpoint_accel.cpp.

void mavplugin::SetpointPositionPlugin::send_setpoint_transform ( const tf::Transform transform,
const ros::Time stamp 
) [inline, private]

Send transform to FCU position controller

Note: send only XYZ, Yaw

Definition at line 101 of file setpoint_position.cpp.

void mavplugin::SetpointVelocityPlugin::send_setpoint_velocity ( const ros::Time stamp,
float  vx,
float  vy,
float  vz,
float  yaw_rate 
) [inline, private]

Send velocity to FCU velocity controller

Note: send only VX VY VZ. ENU frame.

Definition at line 81 of file setpoint_velocity.cpp.

void mavplugin::FTPPlugin::send_terminate_command ( uint32_t  session) [inline]

Definition at line 618 of file ftp.cpp.

void mavplugin::FTPPlugin::send_truncate_command ( std::string &  path,
size_t  length 
) [inline]

Definition at line 666 of file ftp.cpp.

void mavplugin::WaypointPlugin::send_waypoint ( size_t  seq) [inline, private]

Definition at line 576 of file waypoint.cpp.

void mavplugin::FTPPlugin::send_write_command ( const size_t  bytes_to_copy) [inline]

Definition at line 635 of file ftp.cpp.

void mavplugin::SystemStatusDiag::set ( mavlink_sys_status_t &  st) [inline]

Definition at line 135 of file sys_status.cpp.

void mavplugin::BatteryStatusDiag::set ( float  volt,
float  curr,
float  rem 
) [inline]

Definition at line 215 of file sys_status.cpp.

void mavplugin::MemInfo::set ( uint16_t  f,
uint16_t  b 
) [inline]

Definition at line 255 of file sys_status.cpp.

void mavplugin::HwStatus::set ( uint16_t  v,
uint8_t  e 
) [inline]

Definition at line 292 of file sys_status.cpp.

void mavplugin::SetpointAttitudePlugin::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 
) [inline, private]

Definition at line 118 of file setpoint_attitude.cpp.

bool mavplugin::ParamPlugin::set_cb ( mavros::ParamSet::Request &  req,
mavros::ParamSet::Response &  res 
) [inline, private]

sets parameter value ~param/set

Definition at line 843 of file param.cpp.

bool mavplugin::WaypointPlugin::set_cur_cb ( mavros::WaypointSetCurrent::Request &  req,
mavros::WaypointSetCurrent::Response &  res 
) [inline, private]

Definition at line 797 of file waypoint.cpp.

void mavplugin::WaypointPlugin::set_current_waypoint ( size_t  seq) [inline, private]

Definition at line 611 of file waypoint.cpp.

void mavplugin::FTPRequest::set_data_string ( std::string &  s) [inline]

Copy string to payload.

Parameters:
[in]spayload string
Note:
this function allow null termination inside string it used to send multiple strings in one message

Definition at line 138 of file ftp.cpp.

void mavplugin::GPSInfo::set_gps_raw ( mavlink_gps_raw_int_t &  gps) [inline]

Definition at line 49 of file gps.cpp.

bool mavplugin::CommandPlugin::set_home_cb ( mavros::CommandHome::Request &  req,
mavros::CommandHome::Response &  res 
) [inline, private]

Definition at line 294 of file command.cpp.

void mavplugin::BatteryStatusDiag::set_min_voltage ( float  volt) [inline]

Definition at line 210 of file sys_status.cpp.

bool mavplugin::SystemStatusPlugin::set_mode_cb ( mavros::SetMode::Request &  req,
mavros::SetMode::Response &  res 
) [inline, private]

Definition at line 590 of file sys_status.cpp.

template<class D>
void mavplugin::SetPositionTargetLocalNEDMixin< D >::set_position_target_local_ned ( uint32_t  time_boot_ms,
uint8_t  coordinate_frame,
uint16_t  type_mask,
float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz,
float  afx,
float  afy,
float  afz,
float  yaw,
float  yaw_rate 
) [inline]

Definition at line 44 of file setpoint_mixin.h.

bool mavplugin::SystemStatusPlugin::set_rate_cb ( mavros::StreamRate::Request &  req,
mavros::StreamRate::Response &  res 
) [inline, private]

Definition at line 575 of file sys_status.cpp.

void mavplugin::TimeSyncStatus::set_timestamp ( uint64_t  timestamp_us) [inline]

Definition at line 80 of file sys_time.cpp.

Definition at line 125 of file setpoint_position.cpp.

Definition at line 45 of file setpoint_accel.cpp.

Definition at line 47 of file setpoint_attitude.cpp.

Definition at line 44 of file setpoint_position.cpp.

Definition at line 44 of file setpoint_velocity.cpp.

void mavplugin::IMUPubPlugin::setup_covariance ( boost::array< double, 9 > &  cov,
double  stdev 
) [inline, private]

Definition at line 123 of file imu_pub.cpp.

void mavplugin::ParamPlugin::shedule_cb ( const ros::TimerEvent event) [inline, private]

Definition at line 596 of file param.cpp.

void mavplugin::WaypointPlugin::shedule_pull ( const ros::Duration dt) [inline, private]

Definition at line 570 of file waypoint.cpp.

void mavplugin::ParamPlugin::shedule_pull ( const ros::Duration dt) [inline, private]

Definition at line 590 of file param.cpp.

void mavplugin::WaypointPlugin::sheduled_pull_cb ( const ros::TimerEvent event) [inline, private]

Definition at line 528 of file waypoint.cpp.

void mavplugin::SystemTimePlugin::sys_time_cb ( const ros::TimerEvent event) [inline, private]

Definition at line 243 of file sys_time.cpp.

mavplugin::SystemStatusDiag::SystemStatusDiag ( const std::string  name) [inline]

Definition at line 130 of file sys_status.cpp.

Definition at line 331 of file sys_status.cpp.

Definition at line 137 of file sys_time.cpp.

bool mavplugin::CommandPlugin::takeoff_cb ( mavros::CommandTOL::Request &  req,
mavros::CommandTOL::Response &  res 
) [inline, private]

Definition at line 303 of file command.cpp.

Definition at line 102 of file 3dr_radio.cpp.

mavplugin::TDRRadioStatus::TDRRadioStatus ( const std::string  name,
uint8_t  _low_rssi 
) [inline]

Definition at line 37 of file 3dr_radio.cpp.

template<class D>
void mavplugin::TFListenerMixin< D >::tf_listener ( void  ) [inline]

Definition at line 93 of file setpoint_mixin.h.

template<class D>
void mavplugin::TFListenerMixin< D >::tf_start ( const char *  _thd_name,
void(D::*)(const tf::Transform &, const ros::Time &)  cbp 
) [inline]

start tf listener

Parameters:
_thd_namelistener thread name
cbpplugin callback function

Definition at line 84 of file setpoint_mixin.h.

Definition at line 227 of file setpoint_attitude.cpp.

void mavplugin::TimeSyncStatus::tick ( int64_t  dt,
uint64_t  timestamp_us 
) [inline]

Definition at line 72 of file sys_time.cpp.

void mavplugin::WaypointPlugin::timeout_cb ( const ros::TimerEvent event) [inline, private]

Definition at line 477 of file waypoint.cpp.

void mavplugin::SystemStatusPlugin::timeout_cb ( const ros::TimerEvent event) [inline, private]

Definition at line 556 of file sys_status.cpp.

void mavplugin::ParamPlugin::timeout_cb ( const ros::TimerEvent event) [inline, private]

Definition at line 613 of file param.cpp.

mavplugin::TimeSyncStatus::TimeSyncStatus ( const std::string  name,
size_t  win_size 
) [inline]

Definition at line 43 of file sys_time.cpp.

static int64_t mavplugin::Parameter::to_integer ( param_t p) [inline, static]

For get/set services

Definition at line 237 of file param.cpp.

static mavros::Waypoint mavplugin::WaypointItem::to_msg ( WaypointItem wp) [inline, static]

Definition at line 56 of file waypoint.cpp.

Convert internal type to mavlink_param_union_t

Definition at line 151 of file param.cpp.

Definition at line 430 of file param.cpp.

Variation of Parameter::to_param_union with quirks for ArduPilotMega

Definition at line 194 of file param.cpp.

static double mavplugin::Parameter::to_real ( param_t p) [inline, static]

Definition at line 254 of file param.cpp.

static std::string mavplugin::WaypointItem::to_string_command ( WaypointItem wpi) [inline, static]

Definition at line 126 of file waypoint.cpp.

static std::string mavplugin::WaypointItem::to_string_frame ( WaypointItem wpi) [inline, static]

Definition at line 112 of file waypoint.cpp.

static std::string mavplugin::Parameter::to_string_vt ( param_t  p) [inline, static]

Convert internal type to std::string (for debugging)

Definition at line 123 of file param.cpp.

Convert internal value to rosparam XmlRpcValue

Definition at line 264 of file param.cpp.

bool mavplugin::FTPPlugin::truncate_cb ( mavros::FileTruncate::Request &  req,
mavros::FileTruncate::Response &  res 
) [inline]

Definition at line 988 of file ftp.cpp.

void mavplugin::FTPPlugin::truncate_file ( std::string &  path,
size_t  length 
) [inline]

Definition at line 824 of file ftp.cpp.

Definition at line 206 of file setpoint_attitude.cpp.

void mavplugin::IMUPubPlugin::uas_store_attitude ( tf::Quaternion orientation,
geometry_msgs::Vector3 &  gyro_vec,
geometry_msgs::Vector3 &  acc_vec 
) [inline, private]

Definition at line 132 of file imu_pub.cpp.

Definition at line 100 of file setpoint_velocity.cpp.

Definition at line 41 of file vfr_hud.cpp.

Definition at line 131 of file command.cpp.

bool mavplugin::FTPPlugin::wait_completion ( const int  msecs) [inline]

Definition at line 854 of file ftp.cpp.

bool mavplugin::WaypointPlugin::wait_fetch_all ( ) [inline, private]

Definition at line 595 of file waypoint.cpp.

bool mavplugin::ParamPlugin::wait_fetch_all ( ) [inline, private]

Definition at line 693 of file param.cpp.

Definition at line 701 of file param.cpp.

bool mavplugin::WaypointPlugin::wait_push_all ( ) [inline, private]

Definition at line 603 of file waypoint.cpp.

Definition at line 151 of file waypoint.cpp.

Definition at line 849 of file ftp.cpp.

bool mavplugin::FTPPlugin::write_cb ( mavros::FileWrite::Request &  req,
mavros::FileWrite::Response &  res 
) [inline]

Definition at line 948 of file ftp.cpp.

bool mavplugin::FTPPlugin::write_file ( std::string &  path,
size_t  off,
V_FileData data 
) [inline]

Definition at line 796 of file ftp.cpp.

Definition at line 791 of file ftp.cpp.

virtual mavplugin::MavRosPlugin::~MavRosPlugin ( ) [inline, virtual]

Definition at line 62 of file mavros_plugin.h.


Variable Documentation

Definition at line 75 of file setpoint_accel.cpp.

std::condition_variable mavplugin::CommandTransaction::ack

Definition at line 43 of file command.cpp.

std::condition_variable mavplugin::ParamSetOpt::ack

Definition at line 336 of file param.cpp.

Definition at line 108 of file command.cpp.

constexpr int mavplugin::CommandPlugin::ACK_TIMEOUT_MS = 5000 [static, private]

Definition at line 106 of file command.cpp.

std::list<CommandTransaction *> mavplugin::CommandPlugin::ack_waiting_list [private]

Definition at line 105 of file command.cpp.

session id of current operation

Definition at line 284 of file ftp.cpp.

boost::array<double, 9> mavplugin::IMUPubPlugin::angular_velocity_cov [private]

Definition at line 110 of file imu_pub.cpp.

Definition at line 99 of file command.cpp.

Definition at line 107 of file setpoint_attitude.cpp.

Definition at line 47 of file waypoint.cpp.

BatteryStatusDiag mavplugin::SystemStatusPlugin::batt_diag [private]

Definition at line 413 of file sys_status.cpp.

Definition at line 418 of file sys_status.cpp.

Definition at line 254 of file waypoint.cpp.

Definition at line 403 of file param.cpp.

constexpr int mavplugin::WaypointPlugin::BOOTUP_TIME_MS = 15000 [static, private]

Definition at line 248 of file waypoint.cpp.

constexpr int mavplugin::ParamPlugin::BOOTUP_TIME_MS = 10000 [static, private]

APM boot time.

Definition at line 398 of file param.cpp.

uint16_t mavplugin::MemInfo::brkval [private]

Definition at line 278 of file sys_status.cpp.

Definition at line 312 of file ftp.cpp.

Definition at line 267 of file ftp.cpp.

frame for TF and Pose

Definition at line 81 of file local_position.cpp.

Definition at line 90 of file setpoint_position.cpp.

frame for TF and Pose

Definition at line 102 of file global_position.cpp.

Definition at line 111 of file setpoint_attitude.cpp.

constexpr int mavplugin::FTPPlugin::CHUNK_TIMEOUT_MS = 200 [static]

Definition at line 319 of file ftp.cpp.

Definition at line 216 of file waypoint.cpp.

Definition at line 258 of file ftp.cpp.

Definition at line 96 of file command.cpp.

Definition at line 45 of file waypoint.cpp.

Definition at line 98 of file command.cpp.

Definition at line 97 of file command.cpp.

std::condition_variable mavplugin::FTPPlugin::cond

wait condvar

Definition at line 287 of file ftp.cpp.

Definition at line 42 of file command.cpp.

Definition at line 286 of file ftp.cpp.

Definition at line 335 of file param.cpp.

Definition at line 119 of file sys_time.cpp.

Definition at line 46 of file waypoint.cpp.

Definition at line 240 of file sys_status.cpp.

command data, varies by Opcode

Definition at line 69 of file ftp.cpp.

const uint8_t mavplugin::FTPRequest::DATA_MAXSZ = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(PayloadHeader) [static]

Definition at line 109 of file ftp.cpp.

Definition at line 92 of file 3dr_radio.cpp.

const char mavplugin::FTPRequest::DIRENT_DIR = 'D' [static]

Definition at line 107 of file ftp.cpp.

const char mavplugin::FTPRequest::DIRENT_FILE = 'F' [static]

Definition at line 106 of file ftp.cpp.

const char mavplugin::FTPRequest::DIRENT_SKIP = 'S' [static]

Definition at line 108 of file ftp.cpp.

Definition at line 245 of file waypoint.cpp.

TimeSyncStatus mavplugin::SystemTimePlugin::dt_diag [private]

Definition at line 184 of file sys_time.cpp.

Definition at line 129 of file sys_time.cpp.

std::atomic<uint16_t> mavplugin::GPSInfo::eph [private]

Definition at line 90 of file gps.cpp.

std::atomic<uint16_t> mavplugin::GPSInfo::epv [private]

Definition at line 91 of file gps.cpp.

Definition at line 44 of file command.cpp.

Definition at line 93 of file global_position.cpp.

Definition at line 141 of file gps.cpp.

std::atomic<int> mavplugin::GPSInfo::fix_type [private]

Definition at line 89 of file gps.cpp.

Definition at line 44 of file waypoint.cpp.

origin for TF

Definition at line 80 of file local_position.cpp.

Definition at line 89 of file setpoint_position.cpp.

std::string mavplugin::IMUPubPlugin::frame_id [private]

Definition at line 96 of file imu_pub.cpp.

origin for TF

Definition at line 101 of file global_position.cpp.

Definition at line 110 of file setpoint_attitude.cpp.

std::string mavplugin::GPSPlugin::frame_id [private]

Definition at line 136 of file gps.cpp.

Definition at line 186 of file sys_time.cpp.

ssize_t mavplugin::MemInfo::freemem [private]

Definition at line 277 of file sys_status.cpp.

Definition at line 254 of file ftp.cpp.

constexpr double mavplugin::IMUPubPlugin::GAUSS_TO_TESLA = 1.0e-4 [static, private]

Definition at line 115 of file imu_pub.cpp.

Definition at line 393 of file param.cpp.

Definition at line 218 of file waypoint.cpp.

Definition at line 92 of file global_position.cpp.

GPSInfo mavplugin::GPSPlugin::gps_diag [private]

Definition at line 139 of file gps.cpp.

Definition at line 103 of file command.cpp.

Definition at line 107 of file imu_pub.cpp.

Definition at line 105 of file imu_pub.cpp.

Definition at line 130 of file 3dr_radio.cpp.

Definition at line 80 of file rc_io.cpp.

Definition at line 106 of file imu_pub.cpp.

HeartbeatStatus mavplugin::SystemStatusPlugin::hb_diag [private]

Definition at line 409 of file sys_status.cpp.

Definition at line 96 of file global_position.cpp.

Definition at line 415 of file sys_status.cpp.

Definition at line 117 of file sys_status.cpp.

Definition at line 122 of file sys_time.cpp.

Definition at line 411 of file sys_status.cpp.

size_t mavplugin::HwStatus::i2cerr [private]

Definition at line 319 of file sys_status.cpp.

Definition at line 320 of file sys_status.cpp.

Definition at line 99 of file imu_pub.cpp.

Definition at line 100 of file imu_pub.cpp.

error signaling flag (timeout/proto error)

Definition at line 288 of file ftp.cpp.

Definition at line 237 of file waypoint.cpp.

Definition at line 334 of file param.cpp.

Definition at line 419 of file param.cpp.

Definition at line 102 of file command.cpp.

Definition at line 128 of file sys_time.cpp.

Definition at line 123 of file sys_status.cpp.

mavlink_radio_status_t mavplugin::TDRRadioStatus::last_rst

Definition at line 90 of file 3dr_radio.cpp.

seqNumber for send.

Definition at line 283 of file ftp.cpp.

mavlink_sys_status_t mavplugin::SystemStatusDiag::last_st [private]

Definition at line 195 of file sys_status.cpp.

Definition at line 130 of file sys_time.cpp.

geometry_msgs::Vector3 mavplugin::IMUPubPlugin::linear_accel_vec [private]

Definition at line 108 of file imu_pub.cpp.

boost::array<double, 9> mavplugin::IMUPubPlugin::linear_acceleration_cov [private]

Definition at line 109 of file imu_pub.cpp.

Definition at line 420 of file param.cpp.

std::vector<mavros::FileEntry> mavplugin::FTPPlugin::list_entries

Definition at line 294 of file ftp.cpp.

Definition at line 292 of file ftp.cpp.

Definition at line 293 of file ftp.cpp.

std::condition_variable mavplugin::WaypointPlugin::list_receiving [private]

Definition at line 240 of file waypoint.cpp.

std::condition_variable mavplugin::ParamPlugin::list_receiving [private]

Definition at line 421 of file param.cpp.

std::condition_variable mavplugin::WaypointPlugin::list_sending [private]

Definition at line 241 of file waypoint.cpp.

Definition at line 256 of file ftp.cpp.

Definition at line 255 of file waypoint.cpp.

Definition at line 404 of file param.cpp.

constexpr int mavplugin::WaypointPlugin::LIST_TIMEOUT_MS = 30000 [static, private]

system startup delay before start pull

Definition at line 249 of file waypoint.cpp.

constexpr int mavplugin::FTPPlugin::LIST_TIMEOUT_MS = 5000 [static]

Definition at line 317 of file ftp.cpp.

constexpr int mavplugin::ParamPlugin::LIST_TIMEOUT_MS = 30000 [static, private]

Receive all time.

Definition at line 400 of file param.cpp.

Definition at line 77 of file local_position.cpp.

Definition at line 93 of file 3dr_radio.cpp.

Definition at line 101 of file imu_pub.cpp.

boost::array<double, 9> mavplugin::IMUPubPlugin::magnetic_cov [private]

Definition at line 113 of file imu_pub.cpp.

Definition at line 121 of file sys_status.cpp.

const double mavplugin::TimeSyncStatus::max_freq_ [private]

Definition at line 126 of file sys_time.cpp.

constexpr size_t mavplugin::FTPPlugin::MAX_RESERVE_DIFF = 0x10000 [static]

Maximum difference between allocated space and used.

Definition at line 322 of file ftp.cpp.

Definition at line 410 of file sys_status.cpp.

constexpr double mavplugin::IMUPubPlugin::MILLIBAR_TO_PASCAL = 1.0e2 [static, private]

Definition at line 119 of file imu_pub.cpp.

constexpr double mavplugin::IMUPubPlugin::MILLIG_TO_MS2 = 9.80665 / 1000.0 [static, private]

Definition at line 118 of file imu_pub.cpp.

constexpr double mavplugin::IMUPubPlugin::MILLIRS_TO_RADSEC = 1.0e-3 [static, private]

Definition at line 117 of file imu_pub.cpp.

constexpr double mavplugin::IMUPubPlugin::MILLIT_TO_TESLA = 1000.0 [static, private]

Definition at line 116 of file imu_pub.cpp.

Definition at line 120 of file sys_status.cpp.

const double mavplugin::TimeSyncStatus::min_freq_ [private]

Definition at line 125 of file sys_time.cpp.

Definition at line 242 of file sys_status.cpp.

Definition at line 261 of file ftp.cpp.

Definition at line 420 of file sys_status.cpp.

std::recursive_mutex mavplugin::RCIOPlugin::mutex [private]

Definition at line 75 of file rc_io.cpp.

std::recursive_mutex mavplugin::CommandPlugin::mutex [private]

Definition at line 93 of file command.cpp.

std::recursive_mutex mavplugin::HeartbeatStatus::mutex

Definition at line 118 of file sys_status.cpp.

std::recursive_mutex mavplugin::TimeSyncStatus::mutex [private]

Definition at line 123 of file sys_time.cpp.

std::recursive_mutex mavplugin::SystemStatusDiag::mutex [private]

Definition at line 194 of file sys_status.cpp.

std::recursive_mutex mavplugin::WaypointPlugin::mutex [private]

Definition at line 209 of file waypoint.cpp.

std::recursive_mutex mavplugin::BatteryStatusDiag::mutex [private]

Definition at line 238 of file sys_status.cpp.

std::recursive_mutex mavplugin::MemInfo::mutex [private]

Definition at line 276 of file sys_status.cpp.

std::recursive_mutex mavplugin::HwStatus::mutex [private]

Definition at line 317 of file sys_status.cpp.

std::recursive_mutex mavplugin::ParamPlugin::mutex [private]

Definition at line 386 of file param.cpp.

Offsets for List and Read commands.

Definition at line 68 of file ftp.cpp.

Definition at line 282 of file ftp.cpp.

Command opcode.

Definition at line 64 of file ftp.cpp.

Definition at line 297 of file ftp.cpp.

Definition at line 298 of file ftp.cpp.

Definition at line 257 of file ftp.cpp.

constexpr int mavplugin::FTPPlugin::OPEN_TIMEOUT_MS = 200 [static]

Definition at line 318 of file ftp.cpp.

boost::array<double, 9> mavplugin::IMUPubPlugin::orientation_cov [private]

Definition at line 111 of file imu_pub.cpp.

Definition at line 85 of file rc_io.cpp.

32 bit aligment padding

Definition at line 67 of file ftp.cpp.

Definition at line 330 of file param.cpp.

Definition at line 48 of file waypoint.cpp.

Definition at line 49 of file waypoint.cpp.

Definition at line 50 of file waypoint.cpp.

Definition at line 51 of file waypoint.cpp.

Definition at line 52 of file param.cpp.

Definition at line 410 of file param.cpp.

Definition at line 49 of file param.cpp.

Definition at line 51 of file param.cpp.

Definition at line 389 of file param.cpp.

Definition at line 418 of file param.cpp.

enum { ... } mavplugin::ParamPlugin::param_state [private]

Definition at line 405 of file param.cpp.

constexpr int mavplugin::ParamPlugin::PARAM_TIMEOUT_MS = 1000 [static, private]

Param wait time.

Definition at line 399 of file param.cpp.

Definition at line 50 of file param.cpp.

std::map<std::string, Parameter> mavplugin::ParamPlugin::parameters [private]

Definition at line 407 of file param.cpp.

std::list<uint16_t> mavplugin::ParamPlugin::parameters_missing_idx [private]

Definition at line 408 of file param.cpp.

Definition at line 76 of file local_position.cpp.

Definition at line 94 of file global_position.cpp.

Definition at line 103 of file imu_pub.cpp.

Definition at line 214 of file waypoint.cpp.

Definition at line 390 of file param.cpp.

Definition at line 215 of file waypoint.cpp.

Definition at line 391 of file param.cpp.

store errno from server

Definition at line 289 of file ftp.cpp.

Definition at line 419 of file sys_status.cpp.

std::vector<uint16_t> mavplugin::RCIOPlugin::raw_rc_in [private]

Definition at line 78 of file rc_io.cpp.

std::vector<uint16_t> mavplugin::RCIOPlugin::raw_rc_out [private]

Definition at line 79 of file rc_io.cpp.

Definition at line 83 of file rc_io.cpp.

Definition at line 82 of file rc_io.cpp.

Definition at line 84 of file rc_io.cpp.

Definition at line 304 of file ftp.cpp.

Definition at line 303 of file ftp.cpp.

Definition at line 302 of file ftp.cpp.

Definition at line 259 of file ftp.cpp.

Definition at line 238 of file waypoint.cpp.

Definition at line 97 of file global_position.cpp.

Definition at line 241 of file sys_status.cpp.

Definition at line 263 of file ftp.cpp.

Definition at line 264 of file ftp.cpp.

Request opcode returned in kRspAck, kRspNak message.

Definition at line 66 of file ftp.cpp.

Definition at line 266 of file ftp.cpp.

Definition at line 257 of file waypoint.cpp.

constexpr int mavplugin::WaypointPlugin::RESHEDULE_MS = 5000 [static, private]

Definition at line 251 of file waypoint.cpp.

Definition at line 246 of file waypoint.cpp.

Definition at line 45 of file command.cpp.

constexpr int mavplugin::WaypointPlugin::RETRIES_COUNT = 3 [static, private]

Definition at line 252 of file waypoint.cpp.

constexpr int mavplugin::ParamPlugin::RETRIES_COUNT = 3 [static, private]

Definition at line 401 of file param.cpp.

Definition at line 333 of file param.cpp.

Definition at line 114 of file setpoint_attitude.cpp.

Definition at line 262 of file ftp.cpp.

Definition at line 104 of file global_position.cpp.

Definition at line 98 of file safety_area.cpp.

Definition at line 99 of file safety_area.cpp.

std::atomic<int> mavplugin::GPSInfo::satellites_visible [private]

Definition at line 88 of file gps.cpp.

Definition at line 239 of file waypoint.cpp.

Definition at line 77 of file setpoint_accel.cpp.

Definition at line 82 of file local_position.cpp.

Definition at line 103 of file global_position.cpp.

std::vector<WaypointItem> mavplugin::WaypointPlugin::send_waypoints [private]

Definition at line 221 of file waypoint.cpp.

Definition at line 43 of file waypoint.cpp.

Definition at line 116 of file sys_status.cpp.

std::vector<int> mavplugin::TimeSyncStatus::seq_nums_ [private]

Definition at line 121 of file sys_time.cpp.

sequence number for message

Definition at line 62 of file ftp.cpp.

Session id for read and write commands.

Definition at line 63 of file ftp.cpp.

Definition at line 299 of file ftp.cpp.

Definition at line 217 of file waypoint.cpp.

Definition at line 100 of file command.cpp.

std::map<std::string, ParamSetOpt*> mavplugin::ParamPlugin::set_parameters [private]

Definition at line 409 of file param.cpp.

Definition at line 392 of file param.cpp.

Definition at line 87 of file setpoint_position.cpp.

Definition at line 244 of file waypoint.cpp.

for startup shedule fetch

Definition at line 395 of file param.cpp.

Size of data.

Definition at line 65 of file ftp.cpp.

Definition at line 71 of file setpoint_velocity.cpp.

Definition at line 74 of file setpoint_accel.cpp.

Definition at line 86 of file setpoint_position.cpp.

Definition at line 106 of file setpoint_attitude.cpp.

Definition at line 417 of file sys_status.cpp.

Definition at line 132 of file 3dr_radio.cpp.

SystemStatusDiag mavplugin::SystemStatusPlugin::sys_diag [private]

Definition at line 412 of file sys_status.cpp.

Definition at line 183 of file sys_time.cpp.

Definition at line 101 of file command.cpp.

TDRRadioStatus mavplugin::TDRRadioPlugin::tdr_diag [private]

Definition at line 129 of file 3dr_radio.cpp.

Definition at line 102 of file imu_pub.cpp.

Definition at line 78 of file local_position.cpp.

Definition at line 99 of file global_position.cpp.

Definition at line 92 of file setpoint_position.cpp.

Definition at line 113 of file setpoint_attitude.cpp.

template<class D>
std::thread mavplugin::TFListenerMixin< D >::tf_thread

Definition at line 74 of file setpoint_mixin.h.

template<class D>
boost::function<void (const tf::Transform&, const ros::Time&)> mavplugin::TFListenerMixin< D >::tf_transform_cb

Definition at line 76 of file setpoint_mixin.h.

template<class D>
std::string mavplugin::TFListenerMixin< D >::thd_name

Definition at line 75 of file setpoint_mixin.h.

Definition at line 108 of file setpoint_attitude.cpp.

Definition at line 182 of file sys_time.cpp.

Definition at line 188 of file sys_time.cpp.

Definition at line 142 of file gps.cpp.

Definition at line 181 of file sys_time.cpp.

Definition at line 137 of file gps.cpp.

Definition at line 187 of file sys_time.cpp.

for timeout resend

Definition at line 396 of file param.cpp.

Definition at line 414 of file sys_status.cpp.

Definition at line 114 of file sys_status.cpp.

Definition at line 120 of file sys_time.cpp.

Definition at line 122 of file sys_status.cpp.

const double mavplugin::TimeSyncStatus::tolerance_ [private]

Definition at line 127 of file sys_time.cpp.

Definition at line 265 of file ftp.cpp.

Definition at line 69 of file setpoint_velocity.cpp.

Definition at line 72 of file setpoint_accel.cpp.

Definition at line 74 of file local_position.cpp.

Definition at line 76 of file rc_io.cpp.

Definition at line 84 of file setpoint_position.cpp.

Definition at line 90 of file global_position.cpp.

Definition at line 94 of file command.cpp.

Definition at line 96 of file safety_area.cpp.

Definition at line 97 of file imu_pub.cpp.

Definition at line 104 of file setpoint_attitude.cpp.

UAS* mavplugin::GPSPlugin::uas [private]

Definition at line 135 of file gps.cpp.

Definition at line 180 of file sys_time.cpp.

Definition at line 210 of file waypoint.cpp.

Definition at line 387 of file param.cpp.

Definition at line 408 of file sys_status.cpp.

boost::array<double, 9> mavplugin::IMUPubPlugin::unk_orientation_cov [private]

Definition at line 112 of file imu_pub.cpp.

float mavplugin::HwStatus::vcc [private]

Definition at line 318 of file sys_status.cpp.

Definition at line 95 of file global_position.cpp.

Definition at line 143 of file gps.cpp.

Definition at line 72 of file setpoint_velocity.cpp.

Definition at line 72 of file vfr_hud.cpp.

Definition at line 239 of file sys_status.cpp.

std::vector<WaypointItem> mavplugin::WaypointPlugin::waypoints [private]

Definition at line 220 of file waypoint.cpp.

Definition at line 73 of file vfr_hud.cpp.

Definition at line 119 of file sys_status.cpp.

Definition at line 124 of file sys_time.cpp.

Definition at line 232 of file waypoint.cpp.

Definition at line 234 of file waypoint.cpp.

Definition at line 233 of file waypoint.cpp.

Definition at line 213 of file waypoint.cpp.

Definition at line 212 of file waypoint.cpp.

Definition at line 236 of file waypoint.cpp.

Definition at line 235 of file waypoint.cpp.

enum { ... } mavplugin::WaypointPlugin::wp_state [private]

Definition at line 256 of file waypoint.cpp.

constexpr int mavplugin::WaypointPlugin::WP_TIMEOUT_MS = 1000 [static, private]

Timeout for pull/push operations.

Definition at line 250 of file waypoint.cpp.

Definition at line 243 of file waypoint.cpp.

Definition at line 308 of file ftp.cpp.

V_FileData::iterator mavplugin::FTPPlugin::write_it

Definition at line 309 of file ftp.cpp.

Definition at line 307 of file ftp.cpp.

Definition at line 260 of file ftp.cpp.

Definition at line 52 of file waypoint.cpp.

Definition at line 53 of file waypoint.cpp.

Definition at line 54 of file waypoint.cpp.


Friends

friend class SetPositionTargetLocalNEDMixin [friend]

Definition at line 68 of file setpoint_velocity.cpp.

friend class SetPositionTargetLocalNEDMixin [friend]

Definition at line 71 of file setpoint_accel.cpp.

friend class SetPositionTargetLocalNEDMixin [friend]

Definition at line 82 of file setpoint_position.cpp.

friend class TFListenerMixin [friend]

Definition at line 83 of file setpoint_position.cpp.

friend class TFListenerMixin [friend]

Definition at line 103 of file setpoint_attitude.cpp.



mavros
Author(s): Vladimir Ermakov
autogenerated on Wed Aug 26 2015 12:29:13