Classes |
| class | mavplugin::CamIMUSyncPlugin |
| | Camera IMU synchronisation plugin. More...
|
| class | mavplugin::DistanceSensorItem |
| | Distance sensor mapping storage item. More...
|
| class | mavplugin::DistanceSensorPlugin |
| | Distance sensor plugin. More...
|
| class | mavplugin::ImagePubPlugin |
| | Image pub plugin. More...
|
| class | mavplugin::MocapPoseEstimatePlugin |
| | MocapPoseEstimate plugin. More...
|
| class | mavplugin::PX4FlowPlugin |
| | PX4 Optical Flow plugin. More...
|
| class | mavplugin::VibrationPlugin |
| | Vibration plugin. More...
|
| class | mavplugin::VisionPoseEstimatePlugin |
| | Vision pose estimate plugin. More...
|
| class | mavplugin::VisionSpeedEstimatePlugin |
| | Vision speed estimate plugin. More...
|
Namespaces |
| namespace | mavplugin |
Typedefs |
typedef boost::shared_ptr
< MavRosPlugin const > | ConstPtr |
typedef std::lock_guard
< std::recursive_mutex > | lock_guard |
typedef boost::function< void(const
mavlink_message_t *msg,
uint8_t sysid, uint8_t compid | message_handler )) |
typedef std::map< uint8_t,
message_handler > | message_map |
| typedef boost::any | param_t |
typedef boost::shared_ptr
< MavRosPlugin > | Ptr |
typedef boost::shared_ptr
< DistanceSensorItem > | mavplugin::DistanceSensorItem::Ptr |
typedef std::unique_lock
< std::recursive_mutex > | unique_lock |
| typedef std::vector< uint8_t > | V_FileData |
Enumerations |
| enum | ErrorCode |
| enum | Opcode |
| enum | OpState |
Functions |
| void | accel_cb (const geometry_msgs::Vector3Stamped::ConstPtr &req) |
| void | actuator_control_cb (const mavros_msgs::ActuatorControl::ConstPtr &req) |
| | ActuatorControlPlugin () |
| void | add_dirent (const char *ptr, size_t slen) |
| | AltitudePlugin () |
| bool | arming_cb (mavros_msgs::CommandBool::Request &req, mavros_msgs::CommandBool::Response &res) |
| void | attitude_cb (const mavros_msgs::AttitudeTarget::ConstPtr &req) |
| void | autopilot_version_cb (const ros::TimerEvent &event) |
| void | average_offset (int64_t offset_ns) |
| | BatteryStatusDiag (const std::string &name) |
| float | mavplugin::DistanceSensorItem::calculate_variance (float range) |
| | mavplugin::CamIMUSyncPlugin::CamIMUSyncPlugin () |
| static bool | check_exclude_param_id (std::string param_id) |
| bool | mavplugin::ImagePubPlugin::check_supported_type (uint8_t type) const |
| bool | checksum_cb (mavros_msgs::FileChecksum::Request &req, mavros_msgs::FileChecksum::Response &res) |
| | checksum_crc32 (0) |
| void | checksum_crc32_file (std::string &path) |
| void | clear () |
| bool | clear_cb (mavros_msgs::WaypointClear::Request &req, mavros_msgs::WaypointClear::Response &res) |
| bool | close_cb (mavros_msgs::FileClose::Request &req, mavros_msgs::FileClose::Response &res) |
| bool | close_file (std::string &path) |
| void | command_int (bool broadcast, 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 | command_int_cb (mavros_msgs::CommandInt::Request &req, mavros_msgs::CommandInt::Response &res) |
| void | command_long (bool broadcast, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) |
| bool | command_long_cb (mavros_msgs::CommandLong::Request &req, mavros_msgs::CommandLong::Response &res) |
| | CommandPlugin () |
| | CommandTransaction (uint16_t command) |
| static constexpr int | compute_rw_timeout (size_t len) |
| void | connection_cb (bool connected) |
| void | create_directory (std::string &path) |
| static Ptr | mavplugin::DistanceSensorItem::create_item (DistanceSensorPlugin *owner, std::string topic_name) |
| static std::string | custom_version_to_hex_string (uint8_t array[8]) |
| uint8_t * | data () |
| char * | data_c () |
| uint32_t * | data_u32 () |
| bool | decode (UAS *uas, const mavlink_message_t *msg) |
| void | diag_run (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| void | mavplugin::DistanceSensorPlugin::distance_sensor (uint32_t time_boot_ms, uint32_t min_distance, uint32_t max_distance, uint32_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) |
| | mavplugin::DistanceSensorItem::DistanceSensorItem () |
| | mavplugin::DistanceSensorPlugin::DistanceSensorPlugin () |
| | DummyPlugin () |
| void | fill_lla (MsgT &msg, sensor_msgs::NavSatFix::Ptr fix) |
| void | fill_unknown_cov (sensor_msgs::NavSatFix::Ptr fix) |
| static WaypointItem | from_mission_item (mavlink_mission_item_t &mit) |
| static WaypointItem | from_msg (mavros_msgs::Waypoint &wp, uint16_t seq) |
| static param_t | from_param_value (mavlink_param_value_t &pmsg) |
| static param_t | from_param_value_apm_quirk (mavlink_param_value_t &pmsg) |
| static param_t | from_xmlrpc_value (XmlRpc::XmlRpcValue &xml) |
| | FTPPlugin () |
| | FTPRequest () |
| bool | get_cb (mavros_msgs::ParamGet::Request &req, mavros_msgs::ParamGet::Response &res) |
| const message_map | get_rx_handlers () |
| const message_map | mavplugin::CamIMUSyncPlugin::get_rx_handlers () |
| const message_map | mavplugin::VibrationPlugin::get_rx_handlers () |
| const message_map | mavplugin::ImagePubPlugin::get_rx_handlers () |
| const message_map | mavplugin::VisionSpeedEstimatePlugin::get_rx_handlers () |
| const message_map | mavplugin::PX4FlowPlugin::get_rx_handlers () |
| const message_map | mavplugin::MocapPoseEstimatePlugin::get_rx_handlers () |
| const message_map | mavplugin::VisionPoseEstimatePlugin::get_rx_handlers () |
| const message_map | mavplugin::DistanceSensorPlugin::get_rx_handlers () |
| uint8_t | get_target_system_id () |
| void | global_cb (const mavros_msgs::GlobalPositionTarget::ConstPtr &req) |
| | GlobalPositionPlugin () |
| void | go_idle (void) |
| void | go_idle (bool is_error_, int r_errno_=0) |
| void | gps_diag_run (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| void | handle_ack_checksum (FTPRequest &req) |
| void | handle_ack_list (FTPRequest &req) |
| void | handle_ack_open (FTPRequest &req) |
| void | handle_ack_read (FTPRequest &req) |
| void | handle_ack_write (FTPRequest &req) |
| void | handle_altitude (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_attitude (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_attitude_quaternion (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_attitude_target (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_autopilot_version (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | mavplugin::CamIMUSyncPlugin::handle_cam_trig (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_command_ack (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | mavplugin::ImagePubPlugin::handle_data_transmission_handshake (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | mavplugin::DistanceSensorPlugin::handle_distance_sensor (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | mavplugin::ImagePubPlugin::handle_encapsulated_data (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_extended_sys_state (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_file_transfer_protocol (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_global_position_int (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_gps_raw_int (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_heartbeat (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_highres_imu (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_hil_controls (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_local_position_ned (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_manual_control (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_message (msgT &rst, uint8_t sysid, uint8_t compid) |
| void | handle_mission_ack (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_mission_count (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_mission_current (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_mission_item (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_mission_item_reached (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_mission_request (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | mavplugin::PX4FlowPlugin::handle_optical_flow_rad (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_param_value (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_position_target_global_int (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_position_target_local_ned (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_radio_status (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_raw_imu (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_rc_channels (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_rc_channels_raw (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_req_ack (FTPRequest &req) |
| void | handle_req_nack (FTPRequest &req) |
| void | handle_scaled_imu (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_scaled_pressure (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_servo_output_raw (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_statustext (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_sys_status (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_system_time (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_timesync (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | handle_vfr_hud (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| void | mavplugin::VibrationPlugin::handle_vibration (const mavlink_message_t *msg, uint8_t sysid, uint8_t compid) |
| PayloadHeader * | header () |
| void | heartbeat_cb (const ros::TimerEvent &event) |
| | HeartbeatStatus (const std::string &name, size_t win_size) |
| | HilControlsPlugin () |
| | HwStatus (const std::string &name) |
| | mavplugin::ImagePubPlugin::ImagePubPlugin () |
| | IMUPubPlugin () |
| void | initialize (UAS &uas_) |
| void | mavplugin::VibrationPlugin::initialize (UAS &uas_) |
| void | mavplugin::CamIMUSyncPlugin::initialize (UAS &uas_) |
| void | mavplugin::MocapPoseEstimatePlugin::initialize (UAS &uas_) |
| void | mavplugin::VisionSpeedEstimatePlugin::initialize (UAS &uas_) |
| void | mavplugin::PX4FlowPlugin::initialize (UAS &uas_) |
| void | mavplugin::VisionPoseEstimatePlugin::initialize (UAS &uas_) |
| void | mavplugin::ImagePubPlugin::initialize (UAS &uas_) |
| void | mavplugin::DistanceSensorPlugin::initialize (UAS &uas_) |
| bool | is_normalized (float throttle, const float min, const float max) |
| bool | land_cb (mavros_msgs::CommandTOL::Request &req, mavros_msgs::CommandTOL::Response &res) |
| bool | list_cb (mavros_msgs::FileList::Request &req, mavros_msgs::FileList::Response &res) |
| void | list_directory (std::string &path) |
| void | list_directory_end () |
| void | local_cb (const mavros_msgs::PositionTarget::ConstPtr &req) |
| | LocalPositionPlugin () |
| | ManualControlPlugin () |
| | MavRosPlugin (const MavRosPlugin &) |
| | MavRosPlugin () |
| | MemInfo (const std::string &name) |
| void | mission_ack (enum MAV_MISSION_RESULT type) |
| void | mission_clear_all () |
| void | mission_count (uint16_t cnt) |
| void | mission_item (WaypointItem &wp) |
| void | mission_request (uint16_t seq) |
| void | mission_request_list () |
| void | mission_set_current (uint16_t seq) |
| bool | mkdir_cb (mavros_msgs::FileMakeDir::Request &req, mavros_msgs::FileMakeDir::Response &res) |
| void | mavplugin::MocapPoseEstimatePlugin::mocap_pose_cb (const geometry_msgs::PoseStamped::ConstPtr &pose) |
| void | mavplugin::MocapPoseEstimatePlugin::mocap_pose_send (uint64_t usec, float q[4], float x, float y, float z) |
| void | mavplugin::MocapPoseEstimatePlugin::mocap_tf_cb (const geometry_msgs::TransformStamped::ConstPtr &trans) |
| | mavplugin::MocapPoseEstimatePlugin::MocapPoseEstimatePlugin () |
| bool | open_cb (mavros_msgs::FileOpen::Request &req, mavros_msgs::FileOpen::Response &res) |
| bool | open_file (std::string &path, int mode) |
| void | override_cb (const mavros_msgs::OverrideRCIn::ConstPtr req) |
| void | param_request_list () |
| void | param_request_read (std::string id, int16_t index=-1) |
| void | param_set (Parameter ¶m) |
| | ParamPlugin () |
| | ParamSetOpt (Parameter &_p, size_t _rem) |
| void | pose_cb (const geometry_msgs::PoseStamped::ConstPtr &req) |
| void | process_autopilot_version_apm_quirk (mavlink_autopilot_version_t &apv, uint8_t sysid, uint8_t compid) |
| void | process_autopilot_version_normal (mavlink_autopilot_version_t &apv, uint8_t sysid, uint8_t compid) |
| void | process_statustext_normal (uint8_t severity, std::string &text) |
| void | mavplugin::ImagePubPlugin::publish_compressed_image () |
| void | publish_disconnection () |
| void | mavplugin::ImagePubPlugin::publish_image () |
| void | publish_imu_data (uint32_t time_boot_ms, Eigen::Quaterniond &orientation, Eigen::Vector3d &gyro) |
| void | publish_imu_data_raw (std_msgs::Header &header, Eigen::Vector3d &gyro, Eigen::Vector3d &accel) |
| void | publish_mag (std_msgs::Header &header, Eigen::Vector3d &mag_field) |
| void | mavplugin::ImagePubPlugin::publish_raw8u_image () |
| void | publish_waypoints () |
| bool | pull_cb (mavros_msgs::WaypointPull::Request &req, mavros_msgs::WaypointPull::Response &res) |
| bool | pull_cb (mavros_msgs::ParamPull::Request &req, mavros_msgs::ParamPull::Response &res) |
| bool | push_cb (mavros_msgs::ParamPush::Request &req, mavros_msgs::ParamPush::Response &res) |
| bool | push_cb (mavros_msgs::WaypointPush::Request &req, mavros_msgs::WaypointPush::Response &res) |
| | mavplugin::PX4FlowPlugin::PX4FlowPlugin () |
| void | mavplugin::DistanceSensorItem::range_cb (const sensor_msgs::Range::ConstPtr &msg) |
| uint8_t * | raw_payload () |
| void | rc_channels_override (const boost::array< uint16_t, 8 > &channels) |
| | RCIOPlugin () |
| bool | read_cb (mavros_msgs::FileRead::Request &req, mavros_msgs::FileRead::Response &res) |
| bool | read_file (std::string &path, size_t off, size_t len) |
| void | read_file_end () |
| bool | remove_cb (mavros_msgs::FileRemove::Request &req, mavros_msgs::FileRemove::Response &res) |
| void | remove_directory (std::string &path) |
| void | remove_file (std::string &path) |
| bool | rename_ (std::string &old_path, std::string &new_path) |
| bool | rename_cb (mavros_msgs::FileRename::Request &req, mavros_msgs::FileRename::Response &res) |
| void | request_mission_done (void) |
| bool | reset_cb (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
| void | restart_timeout_timer (void) |
| void | restart_timeout_timer_int (void) |
| bool | rmdir_cb (mavros_msgs::FileRemoveDir::Request &req, mavros_msgs::FileRemoveDir::Response &res) |
| void | run (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| void | safety_set_allowed_area (uint8_t coordinate_frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) |
| void | safetyarea_cb (const geometry_msgs::PolygonStamped::ConstPtr &req) |
| | SafetyAreaPlugin () |
| void | send (UAS *uas, uint16_t seqNumber) |
| void | send_any_path_command (FTPRequest::Opcode op, const std::string &debug_msg, std::string &path, uint32_t offset) |
| void | send_attitude_ang_velocity (const ros::Time &stamp, const Eigen::Vector3d &ang_vel) |
| void | send_attitude_target (const ros::Time &stamp, const Eigen::Affine3d &tr) |
| void | send_attitude_throttle (const float throttle) |
| void | send_calc_file_crc32_command (std::string &path) |
| bool | send_command_int (bool broadcast, 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 | send_command_long_and_wait (bool broadcast, 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 | send_create_command () |
| void | send_create_dir_command (std::string &path) |
| void | send_list_command () |
| void | send_open_ro_command () |
| void | send_open_wo_command () |
| bool | send_param_set_and_wait (Parameter ¶m) |
| void | send_position_target (const ros::Time &stamp, const Eigen::Affine3d &tr) |
| void | send_read_command () |
| void | send_remove_command (std::string &path) |
| void | send_remove_dir_command (std::string &path) |
| bool | send_rename_command (std::string &old_path, std::string &new_path) |
| void | send_reset () |
| void | send_safety_set_allowed_area (float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) |
| void | send_setpoint_acceleration (const ros::Time &stamp, Eigen::Vector3d &accel_enu) |
| void | send_setpoint_velocity (const ros::Time &stamp, Eigen::Vector3d &vel_enu, double yaw_rate) |
| void | send_terminate_command (uint32_t session) |
| void | send_timesync_msg (uint64_t tc1, uint64_t ts1) |
| void | send_truncate_command (std::string &path, size_t length) |
| void | mavplugin::VisionPoseEstimatePlugin::send_vision_estimate (const ros::Time &stamp, const Eigen::Affine3d &tr) |
| | Send vision estimate transform to FCU position controller.
|
| void | mavplugin::VisionSpeedEstimatePlugin::send_vision_speed (const geometry_msgs::Vector3 &vel_enu, const ros::Time &stamp) |
| | Send vision speed estimate to FCU velocity controller.
|
| void | send_waypoint (size_t seq) |
| void | send_write_command (const size_t bytes_to_copy) |
| void | set (float volt, float curr, float rem) |
| void | set (uint16_t f, uint16_t b) |
| void | set (uint16_t v, uint8_t e) |
| void | set (mavlink_sys_status_t &st) |
| void | set_actuator_control_target (const uint64_t time_usec, const uint8_t group_mix, const float controls[8]) |
| void | set_attitude_target (uint32_t time_boot_ms, uint8_t type_mask, Eigen::Quaterniond &orientation, Eigen::Vector3d &body_rate, float thrust) |
| void | 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 | set_cb (mavros_msgs::ParamSet::Request &req, mavros_msgs::ParamSet::Response &res) |
| bool | set_cur_cb (mavros_msgs::WaypointSetCurrent::Request &req, mavros_msgs::WaypointSetCurrent::Response &res) |
| void | set_current_waypoint (size_t seq) |
| void | set_data_string (std::string &s) |
| bool | set_home_cb (mavros_msgs::CommandHome::Request &req, mavros_msgs::CommandHome::Response &res) |
| void | set_min_voltage (float volt) |
| bool | set_mode_cb (mavros_msgs::SetMode::Request &req, mavros_msgs::SetMode::Response &res) |
| void | set_position_target_global_int (uint32_t time_boot_ms, uint8_t coordinate_frame, uint8_t type_mask, int32_t lat_int, int32_t lon_int, float alt, Eigen::Vector3d &velocity, Eigen::Vector3d &af, float yaw, float yaw_rate) |
| void | 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 | set_rate_cb (mavros_msgs::StreamRate::Request &req, mavros_msgs::StreamRate::Response &res) |
| void | set_timestamp (uint64_t timestamp_ns) |
| void | setpoint_cb (const geometry_msgs::PoseStamped::ConstPtr &req) |
| | SetpointAccelerationPlugin () |
| | SetpointAttitudePlugin () |
| | SetpointPositionPlugin () |
| | SetpointRawPlugin () |
| | SetpointVelocityPlugin () |
| friend class | SetPositionTargetLocalNEDMixin |
| void | setup_covariance (UAS::Covariance3d &cov, double stdev) |
| void | shedule_cb (const ros::TimerEvent &event) |
| void | shedule_pull (const ros::Duration &dt) |
| void | sheduled_pull_cb (const ros::TimerEvent &event) |
| void | sys_time_cb (const ros::TimerEvent &event) |
| | SystemStatusDiag (const std::string &name) |
| | SystemStatusPlugin () |
| | SystemTimePlugin () |
| bool | takeoff_cb (mavros_msgs::CommandTOL::Request &req, mavros_msgs::CommandTOL::Response &res) |
| | TDRRadioPlugin () |
| void | tf2_start (const char *_thd_name, void(D::*cbp)(const geometry_msgs::TransformStamped &)) |
| friend class | TF2ListenerMixin |
| void | tf_listener (void) |
| void | throttle_cb (const std_msgs::Float64::ConstPtr &req) |
| void | tick (uint8_t type_, uint8_t autopilot_, std::string &mode_, uint8_t system_status_) |
| void | tick (int64_t dt, uint64_t timestamp_ns, int64_t time_offset_ns) |
| void | timeout_cb (const ros::TimerEvent &event) |
| void | timesync_cb (const ros::TimerEvent &event) |
| | TimeSyncStatus (const std::string &name, size_t win_size) |
| static int64_t | to_integer (param_t &p) |
| static mavros_msgs::Waypoint | to_msg (WaypointItem &wp) |
| mavlink_param_union_t | to_param_union (Parameter::param_t p) |
| static mavlink_param_union_t | to_param_union (param_t p) |
| static mavlink_param_union_t | to_param_union_apm_quirk (param_t p) |
| static double | to_real (param_t &p) |
| static std::string | to_string_command (WaypointItem &wpi) |
| static std::string | to_string_frame (WaypointItem &wpi) |
| static std::string | to_string_vt (param_t p) |
| static XmlRpc::XmlRpcValue | to_xmlrpc_value (param_t &p) |
| void | transform_cb (const geometry_msgs::TransformStamped &transform) |
| void | mavplugin::VisionPoseEstimatePlugin::transform_cb (const geometry_msgs::TransformStamped &transform) |
| bool | trigger_control_cb (mavros_msgs::CommandTriggerControl::Request &req, mavros_msgs::CommandTriggerControl::Response &res) |
| bool | truncate_cb (mavros_msgs::FileTruncate::Request &req, mavros_msgs::FileTruncate::Response &res) |
| void | truncate_file (std::string &path, size_t length) |
| void | twist_cb (const geometry_msgs::TwistStamped::ConstPtr &req) |
| void | vel_cb (const geometry_msgs::TwistStamped::ConstPtr &req) |
| void | mavplugin::VisionSpeedEstimatePlugin::vel_speed_cb (const geometry_msgs::Vector3Stamped::ConstPtr &req) |
| void | mavplugin::VisionSpeedEstimatePlugin::vel_twist_cb (const geometry_msgs::TwistStamped::ConstPtr &req) |
| | VfrHudPlugin () |
| | mavplugin::VibrationPlugin::VibrationPlugin () |
| void | mavplugin::VisionPoseEstimatePlugin::vision_cb (const geometry_msgs::PoseStamped::ConstPtr &req) |
| void | mavplugin::VisionPoseEstimatePlugin::vision_cov_cb (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &req) |
| void | mavplugin::VisionPoseEstimatePlugin::vision_position_estimate (uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) |
| void | mavplugin::VisionSpeedEstimatePlugin::vision_speed_estimate (uint64_t usec, float x, float y, float z) |
| | mavplugin::VisionPoseEstimatePlugin::VisionPoseEstimatePlugin () |
| | mavplugin::VisionSpeedEstimatePlugin::VisionSpeedEstimatePlugin () |
| bool | wait_ack_for (CommandTransaction *tr) |
| bool | wait_completion (const int msecs) |
| bool | wait_fetch_all () |
| bool | wait_param_set_ack_for (ParamSetOpt *opt) |
| bool | wait_push_all () |
| | WaypointPlugin () |
| size_t | write_bytes_to_copy () |
| bool | write_cb (mavros_msgs::FileWrite::Request &req, mavros_msgs::FileWrite::Response &res) |
| bool | write_file (std::string &path, size_t off, V_FileData &data) |
| void | write_file_end () |
| virtual | ~MavRosPlugin () |
Variables |
| ros::Subscriber | accel_sub |
| std::condition_variable | ack |
| std::condition_variable | ack |
| const ros::Duration | ACK_TIMEOUT_DT |
| static constexpr int | ACK_TIMEOUT_MS |
| std::list< CommandTransaction * > | ack_waiting_list |
| uint32_t | active_session |
| ros::Subscriber | actuator_control_sub |
| ros::Publisher | altitude_pub |
| UAS::Covariance3d | angular_velocity_cov |
| ros::ServiceServer | arming_srv |
| ros::Subscriber | attitude_sub |
| bool | autocontinue |
| enum MAV_AUTOPILOT | autopilot |
| ros::Timer | autopilot_version_timer |
| BatteryStatusDiag | batt_diag |
| ros::Publisher | batt_pub |
| const ros::Duration | BOOTUP_TIME_DT |
| const ros::Duration | BOOTUP_TIME_DT |
| static constexpr int | BOOTUP_TIME_MS |
| static constexpr int | BOOTUP_TIME_MS |
| std::atomic< uint16_t > | brkval |
| ros::Publisher | mavplugin::CamIMUSyncPlugin::cam_imu_pub |
| ros::NodeHandle | mavplugin::CamIMUSyncPlugin::cam_imu_sync_nh |
| uint32_t | checksum_crc32 |
| ros::ServiceServer | checksum_srv |
| static constexpr int | CHUNK_TIMEOUT_MS |
| | clear |
| ros::ServiceServer | clear_srv |
| ros::ServiceServer | close_srv |
| ros::NodeHandle | cmd_nh |
| enum MAV_CMD | command |
| ros::ServiceServer | command_int_srv |
| ros::ServiceServer | command_long_srv |
| std::condition_variable | cond |
| std::mutex | cond_mutex |
| std::mutex | cond_mutex |
| std::mutex | cond_mutex |
| ros::Publisher | control_pub |
| int | count_ |
| int | count_ |
| int | mavplugin::DistanceSensorItem::covariance |
| | in centimeters, current specification
|
| uint8_t | current |
| float | current |
| uint8_t | data [] |
| std::vector< float > | mavplugin::DistanceSensorItem::data |
| | array allocation for measurements
|
| size_t | mavplugin::DistanceSensorItem::data_index |
| | array index
|
| static const uint8_t | DATA_MAXSZ |
| bool | diag_added |
| std::recursive_mutex | diag_mutex |
| static const char | DIRENT_DIR |
| static const char | DIRENT_FILE |
| static const char | DIRENT_SKIP |
| bool | disable_diag |
| ros::NodeHandle | mavplugin::DistanceSensorPlugin::dist_nh |
| bool | do_pull_after_gcs |
| TimeSyncStatus | dt_diag |
| int64_t | dt_sum |
| uint16_t | expected_command |
| ros::Publisher | extended_state_pub |
| double | mavplugin::DistanceSensorItem::field_of_view |
| | FOV of the sensor.
|
| ros::NodeHandle | mavplugin::PX4FlowPlugin::flow_nh |
| ros::Publisher | mavplugin::PX4FlowPlugin::flow_rad_pub |
| enum MAV_FRAME | frame |
| std::string | frame_id |
| std::string | frame_id |
| std::string | frame_id |
| std::string | frame_id |
| std::string | mavplugin::DistanceSensorItem::frame_id |
| | frame id for send
|
| std::string | mavplugin::VibrationPlugin::frame_id |
| std::string | mavplugin::ImagePubPlugin::frame_id |
| std::string | mavplugin::PX4FlowPlugin::frame_id |
| std::atomic< ssize_t > | freemem |
| ros::NodeHandle | ftp_nh |
| static constexpr double | GAUSS_TO_TESLA |
| ros::ServiceServer | get_srv |
| ros::Subscriber | global_sub |
| ros::Publisher | gp_fix_pub |
| ros::Publisher | gp_hdg_pub |
| ros::NodeHandle | gp_nh |
| ros::Publisher | gp_odom_pub |
| ros::Publisher | gp_rel_alt_pub |
| bool | has_att_quat |
| bool | has_hr_imu |
| bool | has_radio_status |
| bool | has_rc_channels_msg |
| bool | has_scaled_imu |
| HeartbeatStatus | hb_diag |
| ros::Timer | heartbeat_timer |
| ros::NodeHandle | hil_controls_nh |
| ros::Publisher | hil_controls_pub |
| int | hist_indx_ |
| int | hist_indx_ |
| HwStatus | hwst_diag |
| size_t | i2cerr |
| size_t | i2cerr_last |
| std::vector< uint8_t > | mavplugin::ImagePubPlugin::im_buffer |
| size_t | mavplugin::ImagePubPlugin::im_height |
| ros::NodeHandle | mavplugin::ImagePubPlugin::im_nh |
| size_t | mavplugin::ImagePubPlugin::im_packets |
| size_t | mavplugin::ImagePubPlugin::im_payload |
| size_t | mavplugin::ImagePubPlugin::im_seqnr |
| size_t | mavplugin::ImagePubPlugin::im_size |
| uint8_t | mavplugin::ImagePubPlugin::im_type |
| size_t | mavplugin::ImagePubPlugin::im_width |
| image_transport::Publisher | mavplugin::ImagePubPlugin::image_pub |
| ros::NodeHandle | imu_nh |
| ros::Publisher | imu_pub |
| ros::Publisher | imu_raw_pub |
| bool | is_error |
| bool | mavplugin::DistanceSensorItem::is_subscriber |
| | this item is a subscriber, else is a publisher
|
| bool | is_timedout |
| bool | is_timedout |
| bool | is_timedout |
boost::shared_ptr
< image_transport::ImageTransport > | mavplugin::ImagePubPlugin::itp |
| | kCmdBurstReadFile |
| | kCmdCalcFileCRC32 |
| | kCmdCreateDirectory |
| | kCmdCreateFile |
| | kCmdListDirectory |
| | kCmdNone |
| | kCmdOpenFileRO |
| | kCmdOpenFileWO |
| | kCmdReadFile |
| | kCmdRemoveDirectory |
| | kCmdRemoveFile |
| | kCmdRename |
| | kCmdResetSessions |
| | kCmdTerminateSession |
| | kCmdTruncateFile |
| | kCmdWriteFile |
| | kErrEOF |
| | kErrFail |
| | kErrFailErrno |
| | kErrFailFileExists |
| | kErrFailFileProtected |
| | kErrInvalidDataSize |
| | kErrInvalidSession |
| | kErrNone |
| | kErrNoSessionsAvailable |
| | kErrUnknownCommand |
| | kRspAck |
| | kRspNak |
| ros::ServiceServer | land_srv |
| int64_t | last_dt |
| uint16_t | last_send_seqnr |
| mavlink_sys_status_t | last_st |
| mavros_msgs::RadioStatus::Ptr | last_status |
| ros::Time | mavplugin::VisionPoseEstimatePlugin::last_transform_stamp |
| uint64_t | last_ts |
| Eigen::Vector3d | linear_accel_vec |
| UAS::Covariance3d | linear_acceleration_cov |
| std::mutex | list_cond_mutex |
std::vector
< mavros_msgs::FileEntry > | list_entries |
| uint32_t | list_offset |
| std::string | list_path |
| std::condition_variable | list_receiving |
| std::condition_variable | list_receiving |
| std::condition_variable | list_sending |
| ros::ServiceServer | list_srv |
| const ros::Duration | LIST_TIMEOUT_DT |
| const ros::Duration | LIST_TIMEOUT_DT |
| static constexpr int | LIST_TIMEOUT_MS |
| static constexpr int | LIST_TIMEOUT_MS |
| static constexpr int | LIST_TIMEOUT_MS |
| ros::Publisher | local_odom |
| ros::Publisher | local_position |
| ros::Subscriber | local_sub |
| ros::Publisher | local_velocity |
| int | low_rssi |
| ros::NodeHandle | lp_nh |
| ros::Publisher | magn_pub |
| UAS::Covariance3d | magnetic_cov |
| ros::NodeHandle | manual_control_nh |
| static constexpr size_t | mavplugin::ImagePubPlugin::MAX_BUFFER_RESERVE_DIFF = 0x20000 |
| | Maximum difference for im_buffer.capacity() and im_size (100 KiB)
|
| const double | max_freq_ |
| const double | max_freq_ |
| static constexpr size_t | MAX_RESERVE_DIFF |
| MemInfo | mem_diag |
| static constexpr double | MILLIBAR_TO_PASCAL |
| static constexpr double | MILLIG_TO_MS2 |
| static constexpr double | MILLIRS_TO_RADSEC |
| static constexpr double | MILLIT_TO_TESLA |
| const double | min_freq_ |
| const double | min_freq_ |
| float | min_voltage |
| ros::ServiceServer | mkdir_srv |
| ros::Subscriber | mavplugin::MocapPoseEstimatePlugin::mocap_pose_sub |
| ros::Subscriber | mavplugin::MocapPoseEstimatePlugin::mocap_tf_sub |
| std::string | mode |
| ros::ServiceServer | mode_srv |
| ros::NodeHandle | mavplugin::MocapPoseEstimatePlugin::mp_nh |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| std::recursive_mutex | mutex |
| ros::NodeHandle | nh |
| ros::NodeHandle | nh |
| ros::NodeHandle | nh |
| ros::NodeHandle | nh |
| ros::NodeHandle | nh |
| ros::NodeHandle | nh |
| ros::NodeHandle | nh |
| uint32_t | offset |
| int64_t | offset |
| double | offset_avg_alpha |
| | OP_ACK |
| | OP_CHECKSUM |
| | OP_IDLE |
| | OP_LIST |
| | OP_OPEN |
| | OP_READ |
| OpState | op_state |
| | OP_WRITE |
| uint8_t | opcode |
| std::string | open_path |
| size_t | open_size |
| ros::ServiceServer | open_srv |
| static constexpr int | OPEN_TIMEOUT_MS |
| int | mavplugin::DistanceSensorItem::orientation |
| | check orientation of sensor if != -1
|
| UAS::Covariance3d | orientation_cov |
| ros::Subscriber | override_sub |
| DistanceSensorPlugin * | mavplugin::DistanceSensorItem::owner |
| uint8_t | padding [2] |
| Parameter | param |
| float | param1 |
| float | param2 |
| float | param3 |
| float | param4 |
| ssize_t | param_count |
| uint16_t | param_count |
| std::string | param_id |
| uint16_t | param_index |
| ros::NodeHandle | param_nh |
| size_t | param_rx_retries |
| enum mavplugin::ParamPlugin:: { ... } | param_state |
| const ros::Duration | PARAM_TIMEOUT_DT |
| static constexpr int | PARAM_TIMEOUT_MS |
| param_t | param_value |
| std::map< std::string, Parameter > | parameters |
| std::list< uint16_t > | parameters_missing_idx |
| ros::Subscriber | pose_sub |
| Eigen::Vector3d | mavplugin::DistanceSensorItem::position |
| | sensor position
|
| | PR_IDLE |
| | PR_RXLIST |
| | PR_RXPARAM |
| | PR_TXPARAM |
| ros::Publisher | press_pub |
| ros::Publisher | mavplugin::DistanceSensorItem::pub |
| ros::ServiceServer | pull_srv |
| ros::ServiceServer | pull_srv |
| ros::ServiceServer | push_srv |
| ros::ServiceServer | push_srv |
| int | r_errno |
| static constexpr double | RAD_TO_DEG |
| ros::Publisher | mavplugin::PX4FlowPlugin::range_pub |
| double | mavplugin::PX4FlowPlugin::ranger_fov |
| double | mavplugin::PX4FlowPlugin::ranger_max_range |
| double | mavplugin::PX4FlowPlugin::ranger_min_range |
| ros::ServiceServer | rate_srv |
| ros::Publisher | raw_fix_pub |
| std::vector< uint16_t > | raw_rc_in |
| std::vector< uint16_t > | raw_rc_out |
| ros::Publisher | raw_vel_pub |
| ros::Publisher | rc_in_pub |
| ros::NodeHandle | rc_nh |
| ros::Publisher | rc_out_pub |
| V_FileData | read_buffer |
| uint32_t | read_offset |
| size_t | read_size |
| ros::ServiceServer | read_srv |
| std::mutex | recv_cond_mutex |
| float | remaining |
| ros::ServiceServer | remove_srv |
| ros::ServiceServer | rename_srv |
| uint8_t | req_opcode |
| ros::ServiceServer | reset_srv |
| const ros::Duration | RESHEDULE_DT |
| static constexpr int | RESHEDULE_MS |
| bool | reshedule_pull |
| uint8_t | result |
| static constexpr int | RETRIES_COUNT |
| static constexpr int | RETRIES_COUNT |
| static constexpr int | RETRIES_COUNT |
| size_t | retries_remaining |
| bool | reverse_throttle |
| ros::ServiceServer | rmdir_srv |
| double | rot_cov |
| ros::NodeHandle | safety_nh |
| ros::Subscriber | safetyarea_sub |
| std::mutex | send_cond_mutex |
| bool | send_force |
| bool | mavplugin::DistanceSensorItem::send_tf |
| | defines if a transform is sent or not
|
| std::vector< WaypointItem > | send_waypoints |
| uint8_t | mavplugin::DistanceSensorItem::sensor_id |
| | id of the sensor
|
std::unordered_map< uint8_t,
DistanceSensorItem::Ptr > | mavplugin::DistanceSensorPlugin::sensor_map |
| uint16_t | seq |
| std::vector< int > | seq_nums_ |
| std::vector< int > | seq_nums_ |
| uint16_t | seqNumber |
| uint8_t | session |
| std::map< std::string, uint32_t > | session_file_map |
| ros::ServiceServer | set_cur_srv |
| ros::ServiceServer | set_home_srv |
std::map< std::string,
ParamSetOpt * > | set_parameters |
| ros::ServiceServer | set_srv |
| ros::Subscriber | setpoint_sub |
| ros::Timer | shedule_timer |
| ros::Timer | shedule_timer |
| uint8_t | size |
| ros::NodeHandle | sp_nh |
| ros::NodeHandle | sp_nh |
| ros::NodeHandle | sp_nh |
| ros::NodeHandle | sp_nh |
| ros::NodeHandle | sp_nh |
| ros::NodeHandle | mavplugin::VisionSpeedEstimatePlugin::sp_nh |
| ros::NodeHandle | mavplugin::VisionPoseEstimatePlugin::sp_nh |
| ros::Publisher | state_pub |
| ros::Publisher | status_pub |
| ros::Subscriber | mavplugin::DistanceSensorItem::sub |
| SystemStatusDiag | sys_diag |
| ros::Timer | sys_time_timer |
| enum MAV_STATE | system_status |
| ros::ServiceServer | takeoff_srv |
| ros::Publisher | target_attitude_pub |
| ros::Publisher | target_global_pub |
| ros::Publisher | target_local_pub |
| ros::Publisher | temp_pub |
| ros::Publisher | mavplugin::PX4FlowPlugin::temp_pub |
| std::string | tf_child_frame_id |
| std::string | tf_child_frame_id |
| std::string | tf_child_frame_id |
| std::string | tf_child_frame_id |
| std::string | mavplugin::VisionPoseEstimatePlugin::tf_child_frame_id |
| std::string | tf_frame_id |
| std::string | tf_frame_id |
| std::string | tf_frame_id |
| std::string | tf_frame_id |
| std::string | mavplugin::VisionPoseEstimatePlugin::tf_frame_id |
| double | tf_rate |
| double | tf_rate |
| double | mavplugin::VisionPoseEstimatePlugin::tf_rate |
| bool | tf_send |
| bool | tf_send |
| bool | tf_send_fcu |
| std::string | tf_thd_name |
| std::thread | tf_thread |
boost::function< void(const
geometry_msgs::TransformStamped &)> | tf_transform_cb |
| ros::Subscriber | throttle_sub |
| int64_t | time_offset_ns |
| ros::Publisher | time_ref_pub |
| std::string | time_ref_source |
| ros::Timer | timeout_timer |
| ros::Timer | timeout_timer |
| std::vector< ros::Time > | times_ |
| std::vector< ros::Time > | times_ |
| ros::Timer | timesync_timer |
| const double | tolerance_ |
| const double | tolerance_ |
| std::string | mavplugin::DistanceSensorItem::topic_name |
| ros::ServiceServer | trigger_srv |
| ros::ServiceServer | truncate_srv |
| ros::Subscriber | twist_sub |
| enum MAV_TYPE | type |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | uas |
| UAS * | mavplugin::CamIMUSyncPlugin::uas |
| UAS * | mavplugin::VibrationPlugin::uas |
| UAS * | mavplugin::VisionSpeedEstimatePlugin::uas |
| UAS * | mavplugin::PX4FlowPlugin::uas |
| UAS * | mavplugin::MocapPoseEstimatePlugin::uas |
| UAS * | mavplugin::VisionPoseEstimatePlugin::uas |
| UAS * | mavplugin::DistanceSensorPlugin::uas |
| UAS::Covariance3d | unk_orientation_cov |
| bool | use_comp_id_system_control |
| float | vcc |
| ros::Subscriber | vel_sub |
| int | version_retries |
| ros::Publisher | vfr_pub |
| ros::NodeHandle | mavplugin::VibrationPlugin::vibe_nh |
| ros::Publisher | mavplugin::VibrationPlugin::vibration_pub |
| ros::Subscriber | mavplugin::VisionPoseEstimatePlugin::vision_cov_sub |
| ros::Subscriber | mavplugin::VisionPoseEstimatePlugin::vision_sub |
| ros::Subscriber | mavplugin::VisionSpeedEstimatePlugin::vision_vel_sub |
| float | voltage |
| std::vector< WaypointItem > | waypoints |
| ros::Publisher | wind_pub |
| const size_t | window_size_ |
| const size_t | window_size_ |
| | WP_CLEAR |
| size_t | wp_count |
| size_t | wp_cur_active |
| size_t | wp_cur_id |
| | WP_IDLE |
| ros::Publisher | wp_list_pub |
| ros::NodeHandle | wp_nh |
| size_t | wp_retries |
| | WP_RXLIST |
| | WP_RXWP |
| size_t | wp_set_active |
| | WP_SET_CUR |
enum
mavplugin::WaypointPlugin:: { ... } | wp_state |
| const ros::Duration | WP_TIMEOUT_DT |
| static constexpr int | WP_TIMEOUT_MS |
| ros::Timer | wp_timer |
| | WP_TXLIST |
| | WP_TXWP |
| V_FileData | write_buffer |
| V_FileData::iterator | write_it |
| uint32_t | write_offset |
| ros::ServiceServer | write_srv |
| double | x_lat |
| double | y_long |
| double | z_alt |
Friends |
| class | mavplugin::DistanceSensorPlugin::DistanceSensorItem |
| class | mavplugin::VisionPoseEstimatePlugin::TF2ListenerMixin |