| 
Public Member Functions | 
| const message_map | get_rx_handlers () | 
|  | Return map with message rx handlers. 
 | 
| void | initialize (UAS &uas_) | 
|  | Plugin initializer. 
 | 
|  | SetpointRawPlugin () | 
| 
Private Member Functions | 
| void | attitude_cb (const mavros_msgs::AttitudeTarget::ConstPtr &req) | 
| void | global_cb (const mavros_msgs::GlobalPositionTarget::ConstPtr &req) | 
| void | handle_attitude_target (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 | local_cb (const mavros_msgs::PositionTarget::ConstPtr &req) | 
| void | set_attitude_target (uint32_t time_boot_ms, uint8_t type_mask, Eigen::Quaterniond &orientation, Eigen::Vector3d &body_rate, float thrust) | 
|  | Message sepecification: http://mavlink.org/messages/common#SET_ATTITIDE_TARGET.
 | 
| 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) | 
|  | Message specification: http://mavlink.org/messages/common#SET_POSITION_TARGET_GLOBAL_INT.
 | 
| 
Private Attributes | 
| ros::Subscriber | attitude_sub | 
| ros::Subscriber | global_sub | 
| ros::Subscriber | local_sub | 
| ros::NodeHandle | sp_nh | 
| ros::Publisher | target_attitude_pub | 
| ros::Publisher | target_global_pub | 
| ros::Publisher | target_local_pub | 
| UAS * | uas | 
| 
Friends | 
| class | SetPositionTargetLocalNEDMixin | 
Setpoint RAW plugin. 
Send position setpoints and publish current state (return loop). User can decide what set of filed needed for operation via IGNORE bits. 
Definition at line 33 of file setpoint_raw.cpp.