MAVROS Plugin system. More...
MAVROS Plugin system.
#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.
Definition at line 43 of file mavros_plugin.h.
#define SERVICE_IDLE_CHECK | ( | ) |
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 |
Definition at line 57 of file mavros_plugin.h.
typedef boost::any mavplugin::Parameter::param_t |
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 |
anonymous enum [private] |
anonymous enum [private] |
Definition at line 222 of file waypoint.cpp.
Error codes returned in Nak response.
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. |
Command opcodes.
void mavplugin::SetpointAccelerationPlugin::accel_cb | ( | const geometry_msgs::Vector3Stamped::ConstPtr & | req | ) | [inline, private] |
Definition at line 108 of file setpoint_accel.cpp.
void mavplugin::FTPPlugin::add_dirent | ( | const char * | ptr, |
size_t | slen | ||
) | [inline] |
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] |
bool mavplugin::FTPPlugin::checksum_cb | ( | mavros::FileChecksum::Request & | req, |
mavros::FileChecksum::Response & | res | ||
) | [inline] |
void mavplugin::FTPPlugin::checksum_crc32_file | ( | std::string & | path | ) | [inline] |
void mavplugin::TimeSyncStatus::clear | ( | ) | [inline] |
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] |
bool mavplugin::FTPPlugin::close_file | ( | std::string & | path | ) | [inline] |
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.
mavplugin::CommandPlugin::CommandPlugin | ( | ) | [inline] |
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] |
void mavplugin::RCIOPlugin::connection_cb | ( | bool | connected | ) | [inline, private] |
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] |
void mavplugin::FTPPlugin::create_directory | ( | std::string & | path | ) | [inline] |
uint8_t* mavplugin::FTPRequest::data | ( | ) | [inline] |
char* mavplugin::FTPRequest::data_c | ( | ) | [inline] |
uint32_t* mavplugin::FTPRequest::data_u32 | ( | ) | [inline] |
bool mavplugin::FTPRequest::decode | ( | UAS * | uas, |
const mavlink_message_t * | msg | ||
) | [inline] |
mavplugin::DummyPlugin::DummyPlugin | ( | ) | [inline] |
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] |
Parameter::param_t mavplugin::ParamPlugin::from_param_value | ( | mavlink_param_value_t & | msg | ) | [inline, private] |
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
static param_t mavplugin::Parameter::from_xmlrpc_value | ( | XmlRpc::XmlRpcValue & | xml | ) | [inline, static] |
mavplugin::FTPPlugin::FTPPlugin | ( | ) | [inline] |
mavplugin::FTPRequest::FTPRequest | ( | ) | [inline] |
bool mavplugin::ParamPlugin::get_cb | ( | mavros::ParamGet::Request & | req, |
mavros::ParamGet::Response & | res | ||
) | [inline, private] |
std::string const mavplugin::DummyPlugin::get_name | ( | ) | const [inline, virtual] |
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.
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] |
Plugin name (CamelCase)
Implemented in mavplugin::SystemStatusPlugin, mavplugin::ParamPlugin, mavplugin::WaypointPlugin, mavplugin::SystemTimePlugin, mavplugin::GPSPlugin, mavplugin::TDRRadioPlugin, mavplugin::SetpointAttitudePlugin, mavplugin::SafetyAreaPlugin, mavplugin::CommandPlugin, mavplugin::IMUPubPlugin, mavplugin::GlobalPositionPlugin, mavplugin::SetpointPositionPlugin, mavplugin::LocalPositionPlugin, mavplugin::RCIOPlugin, mavplugin::SetpointAccelerationPlugin, mavplugin::SetpointVelocityPlugin, mavplugin::VfrHudPlugin, and mavplugin::DummyPlugin.
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] |
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.
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.
const message_map mavplugin::RCIOPlugin::get_rx_handlers | ( | ) | [inline, virtual] |
Return map with message rx handlers.
Implements mavplugin::MavRosPlugin.
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] |
Return map with message rx handlers.
Implemented in mavplugin::SystemStatusPlugin, mavplugin::ParamPlugin, mavplugin::WaypointPlugin, mavplugin::SystemTimePlugin, mavplugin::GPSPlugin, mavplugin::TDRRadioPlugin, mavplugin::SetpointAttitudePlugin, mavplugin::SafetyAreaPlugin, mavplugin::CommandPlugin, mavplugin::IMUPubPlugin, mavplugin::GlobalPositionPlugin, mavplugin::SetpointPositionPlugin, mavplugin::LocalPositionPlugin, mavplugin::DummyPlugin, mavplugin::RCIOPlugin, mavplugin::SetpointAccelerationPlugin, mavplugin::SetpointVelocityPlugin, and mavplugin::VfrHudPlugin.
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.
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.
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.
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.
uint8_t mavplugin::FTPRequest::get_target_system_id | ( | ) | [inline] |
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] |
void mavplugin::ParamPlugin::go_idle | ( | void | ) | [inline, private] |
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] |
mavplugin::GPSPlugin::GPSPlugin | ( | ) | [inline] |
bool mavplugin::CommandPlugin::guided_cb | ( | mavros::CommandBool::Request & | req, |
mavros::CommandBool::Response & | res | ||
) | [inline, private] |
Definition at line 324 of file command.cpp.
void mavplugin::FTPPlugin::handle_ack_checksum | ( | FTPRequest & | req | ) | [inline] |
void mavplugin::FTPPlugin::handle_ack_list | ( | FTPRequest & | req | ) | [inline] |
void mavplugin::FTPPlugin::handle_ack_open | ( | FTPRequest & | req | ) | [inline] |
void mavplugin::FTPPlugin::handle_ack_read | ( | FTPRequest & | req | ) | [inline] |
void mavplugin::FTPPlugin::handle_ack_write | ( | FTPRequest & | req | ) | [inline] |
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] |
void mavplugin::GlobalPositionPlugin::handle_global_position_int | ( | const mavlink_message_t * | msg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [inline, private] |
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] |
void mavplugin::GPSPlugin::handle_gps_status | ( | const mavlink_message_t * | msg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [inline, private] |
void mavplugin::DummyPlugin::handle_heartbeat | ( | const mavlink_message_t * | msg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [inline, private] |
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.
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] |
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] |
void mavplugin::RCIOPlugin::handle_rc_channels_raw | ( | const mavlink_message_t * | msg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [inline, private] |
void mavplugin::FTPPlugin::handle_req_ack | ( | FTPRequest & | req | ) | [inline] |
void mavplugin::FTPPlugin::handle_req_nack | ( | FTPRequest & | req | ) | [inline] |
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] |
void mavplugin::DummyPlugin::handle_statustext | ( | const mavlink_message_t * | msg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [inline, private] |
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] |
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] |
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.
mavplugin::IMUPubPlugin::IMUPubPlugin | ( | ) | [inline] |
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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
void mavplugin::LocalPositionPlugin::initialize | ( | UAS & | uas, |
ros::NodeHandle & | nh, | ||
diagnostic_updater::Updater & | diag_updater | ||
) | [inline, virtual] |
Plugin initializer.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main diagnostic updater |
Implements mavplugin::MavRosPlugin.
void mavplugin::SetpointVelocityPlugin::initialize | ( | UAS & | uas, |
ros::NodeHandle & | nh, | ||
diagnostic_updater::Updater & | diag_updater | ||
) | [inline, virtual] |
Plugin initializer.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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] |
Plugin initializer.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main diagnostic updater |
Implemented in mavplugin::ParamPlugin, mavplugin::SystemStatusPlugin, mavplugin::WaypointPlugin, mavplugin::SystemTimePlugin, mavplugin::TDRRadioPlugin, mavplugin::GPSPlugin, mavplugin::CommandPlugin, mavplugin::GlobalPositionPlugin, mavplugin::IMUPubPlugin, mavplugin::SetpointAttitudePlugin, mavplugin::SetpointAccelerationPlugin, mavplugin::SetpointPositionPlugin, mavplugin::LocalPositionPlugin, mavplugin::RCIOPlugin, mavplugin::SetpointVelocityPlugin, mavplugin::DummyPlugin, mavplugin::VfrHudPlugin, and mavplugin::SafetyAreaPlugin.
void mavplugin::TDRRadioPlugin::initialize | ( | UAS & | uas, |
ros::NodeHandle & | nh, | ||
diagnostic_updater::Updater & | diag_updater | ||
) | [inline, virtual] |
Plugin initializer.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main diagnostic updater |
Implements mavplugin::MavRosPlugin.
void mavplugin::SystemTimePlugin::initialize | ( | UAS & | uas, |
ros::NodeHandle & | nh, | ||
diagnostic_updater::Updater & | diag_updater | ||
) | [inline, virtual] |
Plugin initializer.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main 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.
[in] | uas | UAS instance (handles FCU connection and some statuses) |
[in] | nh | main mavros ros::NodeHandle (private) |
[in] | diag_updater | main diagnostic updater |
Implements mavplugin::MavRosPlugin.
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] |
void mavplugin::FTPPlugin::list_directory | ( | std::string & | path | ) | [inline] |
void mavplugin::FTPPlugin::list_directory_end | ( | ) | [inline] |
mavplugin::LocalPositionPlugin::LocalPositionPlugin | ( | ) | [inline] |
Definition at line 43 of file local_position.cpp.
mavplugin::MavRosPlugin::MavRosPlugin | ( | const MavRosPlugin & | ) | [private] |
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.
void mavplugin::WaypointPlugin::mission_clear_all | ( | ) | [inline, private] |
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.
void mavplugin::WaypointPlugin::mission_request_list | ( | ) | [inline, private] |
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] |
bool mavplugin::FTPPlugin::open_cb | ( | mavros::FileOpen::Request & | req, |
mavros::FileOpen::Response & | res | ||
) | [inline] |
bool mavplugin::FTPPlugin::open_file | ( | std::string & | path, |
int | mode | ||
) | [inline] |
void mavplugin::RCIOPlugin::override_cb | ( | const mavros::OverrideRCIn::ConstPtr | req | ) | [inline, private] |
void mavplugin::ParamPlugin::param_request_list | ( | ) | [inline, private] |
void mavplugin::ParamPlugin::param_request_read | ( | std::string | id, |
int16_t | index = -1 |
||
) | [inline, private] |
void mavplugin::ParamPlugin::param_set | ( | Parameter & | param | ) | [inline, private] |
mavplugin::ParamPlugin::ParamPlugin | ( | ) | [inline] |
mavplugin::ParamSetOpt::ParamSetOpt | ( | Parameter & | _p, |
size_t | _rem | ||
) | [inline] |
void mavplugin::SetpointAttitudePlugin::pose_cb | ( | const geometry_msgs::PoseStamped::ConstPtr & | req | ) | [inline, private] |
Definition at line 200 of file setpoint_attitude.cpp.
void mavplugin::SetpointAttitudePlugin::pose_cov_cb | ( | const geometry_msgs::PoseWithCovarianceStamped::ConstPtr & | req | ) | [inline, private] |
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
[in] | severity | APM 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
[in] | severity | Levels defined in common.xml |
Definition at line 429 of file sys_status.cpp.
void mavplugin::WaypointPlugin::publish_waypoints | ( | ) | [inline, private] |
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] |
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] |
uint8_t* mavplugin::FTPRequest::raw_payload | ( | ) | [inline] |
void mavplugin::RCIOPlugin::rc_channels_override | ( | const boost::array< uint16_t, 8 > & | channels | ) | [inline, private] |
mavplugin::RCIOPlugin::RCIOPlugin | ( | ) | [inline] |
bool mavplugin::FTPPlugin::read_cb | ( | mavros::FileRead::Request & | req, |
mavros::FileRead::Response & | res | ||
) | [inline] |
bool mavplugin::FTPPlugin::read_file | ( | std::string & | path, |
size_t | off, | ||
size_t | len | ||
) | [inline] |
void mavplugin::FTPPlugin::read_file_end | ( | ) | [inline] |
bool mavplugin::FTPPlugin::remove_cb | ( | mavros::FileRemove::Request & | req, |
mavros::FileRemove::Response & | res | ||
) | [inline] |
void mavplugin::FTPPlugin::remove_directory | ( | std::string & | path | ) | [inline] |
void mavplugin::FTPPlugin::remove_file | ( | std::string & | path | ) | [inline] |
bool mavplugin::FTPPlugin::rename_ | ( | std::string & | old_path, |
std::string & | new_path | ||
) | [inline] |
bool mavplugin::FTPPlugin::rename_cb | ( | mavros::FileRename::Request & | req, |
mavros::FileRename::Response & | res | ||
) | [inline] |
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] |
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] |
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] |
void mavplugin::GPSInfo::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, virtual] |
Implements diagnostic_updater::DiagnosticTask.
void mavplugin::TimeSyncStatus::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, virtual] |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 85 of file sys_time.cpp.
void mavplugin::SystemStatusDiag::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, virtual] |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 140 of file sys_status.cpp.
void mavplugin::BatteryStatusDiag::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, virtual] |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 222 of file sys_status.cpp.
void mavplugin::MemInfo::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, virtual] |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 261 of file sys_status.cpp.
void mavplugin::HwStatus::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, virtual] |
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.
void mavplugin::SafetyAreaPlugin::safetyarea_cb | ( | const geometry_msgs::PolygonStamped::ConstPtr & | req | ) | [inline, private] |
Definition at line 139 of file safety_area.cpp.
mavplugin::SafetyAreaPlugin::SafetyAreaPlugin | ( | ) | [inline] |
Definition at line 42 of file safety_area.cpp.
void mavplugin::FTPRequest::send | ( | UAS * | uas, |
uint16_t | seqNumber | ||
) | [inline] |
void mavplugin::FTPPlugin::send_any_path_command | ( | FTPRequest::Opcode | op, |
const std::string | debug_msg, | ||
std::string & | path, | ||
uint32_t | offset | ||
) | [inline] |
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] |
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++
Definition at line 143 of file command.cpp.
void mavplugin::FTPPlugin::send_create_command | ( | ) | [inline] |
void mavplugin::FTPPlugin::send_create_dir_command | ( | std::string & | path | ) | [inline] |
void mavplugin::FTPPlugin::send_list_command | ( | ) | [inline] |
void mavplugin::FTPPlugin::send_open_ro_command | ( | ) | [inline] |
void mavplugin::FTPPlugin::send_open_wo_command | ( | ) | [inline] |
bool mavplugin::ParamPlugin::send_param_set_and_wait | ( | Parameter & | param | ) | [inline, private] |
void mavplugin::FTPPlugin::send_read_command | ( | ) | [inline] |
void mavplugin::FTPPlugin::send_remove_command | ( | std::string & | path | ) | [inline] |
void mavplugin::FTPPlugin::send_remove_dir_command | ( | std::string & | path | ) | [inline] |
bool mavplugin::FTPPlugin::send_rename_command | ( | std::string & | old_path, |
std::string & | new_path | ||
) | [inline] |
void mavplugin::FTPPlugin::send_reset | ( | ) | [inline] |
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.
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] |
void mavplugin::FTPPlugin::send_truncate_command | ( | std::string & | path, |
size_t | length | ||
) | [inline] |
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] |
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] |
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] |
void mavplugin::GPSInfo::set_gps_raw | ( | mavlink_gps_raw_int_t & | gps | ) | [inline] |
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.
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.
void mavplugin::SetpointPositionPlugin::setpoint_cb | ( | const geometry_msgs::PoseStamped::ConstPtr & | req | ) | [inline, private] |
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] |
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] |
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.
mavplugin::SystemStatusPlugin::SystemStatusPlugin | ( | ) | [inline] |
Definition at line 331 of file sys_status.cpp.
mavplugin::SystemTimePlugin::SystemTimePlugin | ( | ) | [inline] |
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.
mavplugin::TDRRadioPlugin::TDRRadioPlugin | ( | ) | [inline] |
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.
void mavplugin::TFListenerMixin< D >::tf_listener | ( | void | ) | [inline] |
Definition at line 93 of file setpoint_mixin.h.
void mavplugin::TFListenerMixin< D >::tf_start | ( | const char * | _thd_name, |
void(D::*)(const tf::Transform &, const ros::Time &) | cbp | ||
) | [inline] |
start tf listener
_thd_name | listener thread name |
cbp | plugin callback function |
Definition at line 84 of file setpoint_mixin.h.
void mavplugin::SetpointAttitudePlugin::throttle_cb | ( | const std_msgs::Float64::ConstPtr & | req | ) | [inline, private] |
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] |
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] |
static mavros::Waypoint mavplugin::WaypointItem::to_msg | ( | WaypointItem & | wp | ) | [inline, static] |
Definition at line 56 of file waypoint.cpp.
static mavlink_param_union_t mavplugin::Parameter::to_param_union | ( | param_t | p | ) | [inline, static] |
mavlink_param_union_t mavplugin::ParamPlugin::to_param_union | ( | Parameter::param_t | p | ) | [inline, private] |
static mavlink_param_union_t mavplugin::Parameter::to_param_union_apm_quirk | ( | param_t | p | ) | [inline, static] |
Variation of Parameter::to_param_union with quirks for ArduPilotMega
static double mavplugin::Parameter::to_real | ( | param_t & | p | ) | [inline, static] |
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] |
static XmlRpc::XmlRpcValue mavplugin::Parameter::to_xmlrpc_value | ( | param_t & | p | ) | [inline, static] |
bool mavplugin::FTPPlugin::truncate_cb | ( | mavros::FileTruncate::Request & | req, |
mavros::FileTruncate::Response & | res | ||
) | [inline] |
void mavplugin::FTPPlugin::truncate_file | ( | std::string & | path, |
size_t | length | ||
) | [inline] |
void mavplugin::SetpointAttitudePlugin::twist_cb | ( | const geometry_msgs::TwistStamped::ConstPtr & | req | ) | [inline, private] |
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.
void mavplugin::SetpointVelocityPlugin::vel_cb | ( | const geometry_msgs::TwistStamped::ConstPtr & | req | ) | [inline, private] |
Definition at line 100 of file setpoint_velocity.cpp.
mavplugin::VfrHudPlugin::VfrHudPlugin | ( | ) | [inline] |
Definition at line 41 of file vfr_hud.cpp.
bool mavplugin::CommandPlugin::wait_ack_for | ( | CommandTransaction * | tr | ) | [inline, private] |
Definition at line 131 of file command.cpp.
bool mavplugin::FTPPlugin::wait_completion | ( | const int | msecs | ) | [inline] |
bool mavplugin::WaypointPlugin::wait_fetch_all | ( | ) | [inline, private] |
Definition at line 595 of file waypoint.cpp.
bool mavplugin::ParamPlugin::wait_fetch_all | ( | ) | [inline, private] |
bool mavplugin::ParamPlugin::wait_param_set_ack_for | ( | ParamSetOpt * | opt | ) | [inline, private] |
bool mavplugin::WaypointPlugin::wait_push_all | ( | ) | [inline, private] |
Definition at line 603 of file waypoint.cpp.
mavplugin::WaypointPlugin::WaypointPlugin | ( | ) | [inline] |
Definition at line 151 of file waypoint.cpp.
size_t mavplugin::FTPPlugin::write_bytes_to_copy | ( | ) | [inline] |
bool mavplugin::FTPPlugin::write_cb | ( | mavros::FileWrite::Request & | req, |
mavros::FileWrite::Response & | res | ||
) | [inline] |
bool mavplugin::FTPPlugin::write_file | ( | std::string & | path, |
size_t | off, | ||
V_FileData & | data | ||
) | [inline] |
void mavplugin::FTPPlugin::write_file_end | ( | ) | [inline] |
virtual mavplugin::MavRosPlugin::~MavRosPlugin | ( | ) | [inline, virtual] |
Definition at line 62 of file mavros_plugin.h.
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 |
const ros::Duration mavplugin::CommandPlugin::ACK_TIMEOUT_DT [private] |
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.
uint32_t mavplugin::FTPPlugin::active_session |
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.
const ros::Duration mavplugin::WaypointPlugin::BOOTUP_TIME_DT [private] |
Definition at line 254 of file waypoint.cpp.
const ros::Duration mavplugin::ParamPlugin::BOOTUP_TIME_DT [private] |
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] |
uint16_t mavplugin::MemInfo::brkval [private] |
Definition at line 278 of file sys_status.cpp.
uint32_t mavplugin::FTPPlugin::checksum_crc32 |
std::string mavplugin::LocalPositionPlugin::child_frame_id [private] |
frame for TF and Pose
Definition at line 81 of file local_position.cpp.
std::string mavplugin::SetpointPositionPlugin::child_frame_id [private] |
Definition at line 90 of file setpoint_position.cpp.
std::string mavplugin::GlobalPositionPlugin::child_frame_id [private] |
frame for TF and Pose
Definition at line 102 of file global_position.cpp.
std::string mavplugin::SetpointAttitudePlugin::child_frame_id [private] |
Definition at line 111 of file setpoint_attitude.cpp.
constexpr int mavplugin::FTPPlugin::CHUNK_TIMEOUT_MS = 200 [static] |
Definition at line 216 of file waypoint.cpp.
Definition at line 96 of file command.cpp.
enum MAV_CMD mavplugin::WaypointItem::command |
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 |
Definition at line 42 of file command.cpp.
int mavplugin::TimeSyncStatus::count_ [private] |
Definition at line 119 of file sys_time.cpp.
uint8_t mavplugin::WaypointItem::current |
Definition at line 46 of file waypoint.cpp.
float mavplugin::BatteryStatusDiag::current [private] |
Definition at line 240 of file sys_status.cpp.
const uint8_t mavplugin::FTPRequest::DATA_MAXSZ = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(PayloadHeader) [static] |
Definition at line 92 of file 3dr_radio.cpp.
const char mavplugin::FTPRequest::DIRENT_DIR = 'D' [static] |
const char mavplugin::FTPRequest::DIRENT_FILE = 'F' [static] |
const char mavplugin::FTPRequest::DIRENT_SKIP = 'S' [static] |
bool mavplugin::WaypointPlugin::do_pull_after_gcs [private] |
Definition at line 245 of file waypoint.cpp.
TimeSyncStatus mavplugin::SystemTimePlugin::dt_diag [private] |
Definition at line 184 of file sys_time.cpp.
int64_t mavplugin::TimeSyncStatus::dt_sum [private] |
Definition at line 129 of file sys_time.cpp.
std::atomic<uint16_t> mavplugin::GPSInfo::eph [private] |
std::atomic<uint16_t> mavplugin::GPSInfo::epv [private] |
Definition at line 44 of file command.cpp.
Definition at line 93 of file global_position.cpp.
ros::Publisher mavplugin::GPSPlugin::fix_pub [private] |
std::atomic<int> mavplugin::GPSInfo::fix_type [private] |
Definition at line 44 of file waypoint.cpp.
std::string mavplugin::LocalPositionPlugin::frame_id [private] |
origin for TF
Definition at line 80 of file local_position.cpp.
std::string mavplugin::SetpointPositionPlugin::frame_id [private] |
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.
std::string mavplugin::GlobalPositionPlugin::frame_id [private] |
origin for TF
Definition at line 101 of file global_position.cpp.
std::string mavplugin::SetpointAttitudePlugin::frame_id [private] |
Definition at line 110 of file setpoint_attitude.cpp.
std::string mavplugin::GPSPlugin::frame_id [private] |
std::string mavplugin::SystemTimePlugin::frame_id [private] |
Definition at line 186 of file sys_time.cpp.
ssize_t mavplugin::MemInfo::freemem [private] |
Definition at line 277 of file sys_status.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 218 of file waypoint.cpp.
Definition at line 92 of file global_position.cpp.
GPSInfo mavplugin::GPSPlugin::gps_diag [private] |
Definition at line 103 of file command.cpp.
bool mavplugin::IMUPubPlugin::has_att_quat [private] |
Definition at line 107 of file imu_pub.cpp.
bool mavplugin::IMUPubPlugin::has_hr_imu [private] |
Definition at line 105 of file imu_pub.cpp.
bool mavplugin::TDRRadioPlugin::has_radio_status [private] |
Definition at line 130 of file 3dr_radio.cpp.
bool mavplugin::RCIOPlugin::has_rc_channels_msg [private] |
bool mavplugin::IMUPubPlugin::has_scaled_imu [private] |
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.
int mavplugin::TimeSyncStatus::hist_indx_ [private] |
Definition at line 122 of file sys_time.cpp.
HwStatus mavplugin::SystemStatusPlugin::hwst_diag [private] |
Definition at line 411 of file sys_status.cpp.
size_t mavplugin::HwStatus::i2cerr [private] |
Definition at line 319 of file sys_status.cpp.
size_t mavplugin::HwStatus::i2cerr_last [private] |
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.
bool mavplugin::WaypointPlugin::is_timedout [private] |
Definition at line 237 of file waypoint.cpp.
bool mavplugin::ParamPlugin::is_timedout [private] |
Definition at line 102 of file command.cpp.
int64_t mavplugin::TimeSyncStatus::last_dt [private] |
Definition at line 128 of file sys_time.cpp.
mavlink_heartbeat_t mavplugin::HeartbeatStatus::last_hb |
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.
mavlink_sys_status_t mavplugin::SystemStatusDiag::last_st [private] |
Definition at line 195 of file sys_status.cpp.
uint64_t mavplugin::TimeSyncStatus::last_ts [private] |
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.
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 [private] |
Definition at line 240 of file waypoint.cpp.
std::condition_variable mavplugin::ParamPlugin::list_receiving [private] |
std::condition_variable mavplugin::WaypointPlugin::list_sending [private] |
Definition at line 241 of file waypoint.cpp.
const ros::Duration mavplugin::WaypointPlugin::LIST_TIMEOUT_DT [private] |
Definition at line 255 of file waypoint.cpp.
const ros::Duration mavplugin::ParamPlugin::LIST_TIMEOUT_DT [private] |
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] |
constexpr int mavplugin::ParamPlugin::LIST_TIMEOUT_MS = 30000 [static, private] |
Definition at line 77 of file local_position.cpp.
const uint8_t mavplugin::TDRRadioStatus::low_rssi |
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.
const double mavplugin::HeartbeatStatus::max_freq_ |
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] |
MemInfo mavplugin::SystemStatusPlugin::mem_diag [private] |
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.
const double mavplugin::HeartbeatStatus::min_freq_ |
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.
float mavplugin::BatteryStatusDiag::min_voltage [private] |
Definition at line 242 of file sys_status.cpp.
Definition at line 420 of file sys_status.cpp.
std::recursive_mutex mavplugin::RCIOPlugin::mutex [private] |
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] |
OpState mavplugin::FTPPlugin::op_state |
std::string mavplugin::FTPPlugin::open_path |
constexpr int mavplugin::FTPPlugin::OPEN_TIMEOUT_MS = 200 [static] |
boost::array<double, 9> mavplugin::IMUPubPlugin::orientation_cov [private] |
Definition at line 111 of file imu_pub.cpp.
Parameter mavplugin::ParamSetOpt::param |
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.
uint16_t mavplugin::Parameter::param_count |
ssize_t mavplugin::ParamPlugin::param_count [private] |
std::string mavplugin::Parameter::param_id |
uint16_t mavplugin::Parameter::param_index |
size_t mavplugin::ParamPlugin::param_rx_retries [private] |
enum { ... } mavplugin::ParamPlugin::param_state [private] |
const ros::Duration mavplugin::ParamPlugin::PARAM_TIMEOUT_DT [private] |
constexpr int mavplugin::ParamPlugin::PARAM_TIMEOUT_MS = 1000 [static, private] |
std::map<std::string, Parameter> mavplugin::ParamPlugin::parameters [private] |
std::list<uint16_t> mavplugin::ParamPlugin::parameters_missing_idx [private] |
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 215 of file waypoint.cpp.
Definition at line 419 of file sys_status.cpp.
std::vector<uint16_t> mavplugin::RCIOPlugin::raw_rc_in [private] |
std::vector<uint16_t> mavplugin::RCIOPlugin::raw_rc_out [private] |
ros::NodeHandle mavplugin::RCIOPlugin::rc_nh [private] |
V_FileData mavplugin::FTPPlugin::read_buffer |
uint32_t mavplugin::FTPPlugin::read_offset |
Definition at line 238 of file waypoint.cpp.
Definition at line 97 of file global_position.cpp.
float mavplugin::BatteryStatusDiag::remaining [private] |
Definition at line 241 of file sys_status.cpp.
const ros::Duration mavplugin::WaypointPlugin::RESHEDULE_DT [private] |
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.
bool mavplugin::WaypointPlugin::reshedule_pull [private] |
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] |
bool mavplugin::SetpointAttitudePlugin::reverse_throttle [private] |
Definition at line 114 of file setpoint_attitude.cpp.
double mavplugin::GlobalPositionPlugin::rot_cov [private] |
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 239 of file waypoint.cpp.
bool mavplugin::SetpointAccelerationPlugin::send_force [private] |
Definition at line 77 of file setpoint_accel.cpp.
bool mavplugin::LocalPositionPlugin::send_tf [private] |
Definition at line 82 of file local_position.cpp.
bool mavplugin::GlobalPositionPlugin::send_tf [private] |
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.
uint16_t mavplugin::WaypointItem::seq |
Definition at line 43 of file waypoint.cpp.
std::vector<int> mavplugin::HeartbeatStatus::seq_nums_ |
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.
std::map<std::string, uint32_t> mavplugin::FTPPlugin::session_file_map |
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 87 of file setpoint_position.cpp.
Definition at line 244 of file waypoint.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.
double mavplugin::SetpointPositionPlugin::tf_rate [private] |
Definition at line 92 of file setpoint_position.cpp.
double mavplugin::SetpointAttitudePlugin::tf_rate [private] |
Definition at line 113 of file setpoint_attitude.cpp.
std::thread mavplugin::TFListenerMixin< D >::tf_thread |
Definition at line 74 of file setpoint_mixin.h.
boost::function<void (const tf::Transform&, const ros::Time&)> mavplugin::TFListenerMixin< D >::tf_transform_cb |
Definition at line 76 of file setpoint_mixin.h.
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.
uint64_t mavplugin::SystemTimePlugin::time_offset_us [private] |
Definition at line 188 of file sys_time.cpp.
Definition at line 181 of file sys_time.cpp.
std::string mavplugin::GPSPlugin::time_ref_source [private] |
std::string mavplugin::SystemTimePlugin::time_ref_source [private] |
Definition at line 187 of file sys_time.cpp.
Definition at line 414 of file sys_status.cpp.
std::vector<ros::Time> mavplugin::HeartbeatStatus::times_ |
Definition at line 114 of file sys_status.cpp.
std::vector<ros::Time> mavplugin::TimeSyncStatus::times_ [private] |
Definition at line 120 of file sys_time.cpp.
const double mavplugin::HeartbeatStatus::tolerance_ |
Definition at line 122 of file sys_status.cpp.
const double mavplugin::TimeSyncStatus::tolerance_ [private] |
Definition at line 127 of file sys_time.cpp.
UAS* mavplugin::SetpointVelocityPlugin::uas [private] |
Definition at line 69 of file setpoint_velocity.cpp.
UAS* mavplugin::SetpointAccelerationPlugin::uas [private] |
Definition at line 72 of file setpoint_accel.cpp.
UAS* mavplugin::LocalPositionPlugin::uas [private] |
Definition at line 74 of file local_position.cpp.
UAS* mavplugin::RCIOPlugin::uas [private] |
UAS* mavplugin::SetpointPositionPlugin::uas [private] |
Definition at line 84 of file setpoint_position.cpp.
UAS* mavplugin::GlobalPositionPlugin::uas [private] |
Definition at line 90 of file global_position.cpp.
UAS* mavplugin::CommandPlugin::uas [private] |
Definition at line 94 of file command.cpp.
UAS* mavplugin::SafetyAreaPlugin::uas [private] |
Definition at line 96 of file safety_area.cpp.
UAS* mavplugin::IMUPubPlugin::uas [private] |
Definition at line 97 of file imu_pub.cpp.
UAS* mavplugin::SetpointAttitudePlugin::uas [private] |
Definition at line 104 of file setpoint_attitude.cpp.
UAS* mavplugin::GPSPlugin::uas [private] |
UAS* mavplugin::SystemTimePlugin::uas [private] |
Definition at line 180 of file sys_time.cpp.
UAS* mavplugin::WaypointPlugin::uas [private] |
Definition at line 210 of file waypoint.cpp.
UAS* mavplugin::ParamPlugin::uas [private] |
UAS* mavplugin::SystemStatusPlugin::uas [private] |
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.
ros::Publisher mavplugin::GPSPlugin::vel_pub [private] |
Definition at line 72 of file setpoint_velocity.cpp.
Definition at line 72 of file vfr_hud.cpp.
float mavplugin::BatteryStatusDiag::voltage [private] |
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.
const size_t mavplugin::HeartbeatStatus::window_size_ |
Definition at line 119 of file sys_status.cpp.
const size_t mavplugin::TimeSyncStatus::window_size_ [private] |
Definition at line 124 of file sys_time.cpp.
size_t mavplugin::WaypointPlugin::wp_count [private] |
Definition at line 232 of file waypoint.cpp.
size_t mavplugin::WaypointPlugin::wp_cur_active [private] |
Definition at line 234 of file waypoint.cpp.
size_t mavplugin::WaypointPlugin::wp_cur_id [private] |
Definition at line 233 of file waypoint.cpp.
Definition at line 213 of file waypoint.cpp.
Definition at line 212 of file waypoint.cpp.
size_t mavplugin::WaypointPlugin::wp_retries [private] |
Definition at line 236 of file waypoint.cpp.
size_t mavplugin::WaypointPlugin::wp_set_active [private] |
Definition at line 235 of file waypoint.cpp.
enum { ... } mavplugin::WaypointPlugin::wp_state [private] |
const ros::Duration mavplugin::WaypointPlugin::WP_TIMEOUT_DT [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.
V_FileData mavplugin::FTPPlugin::write_buffer |
V_FileData::iterator mavplugin::FTPPlugin::write_it |
uint32_t mavplugin::FTPPlugin::write_offset |
Definition at line 52 of file waypoint.cpp.
Definition at line 53 of file waypoint.cpp.
Definition at line 54 of file waypoint.cpp.
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.