Setpoint attitude plugin. More...

Public Member Functions | |
| const message_map | get_rx_handlers () |
| Return map with message rx handlers. | |
| void | initialize (UAS &uas_) |
| Plugin initializer. | |
| SetpointAttitudePlugin () | |
Private Member Functions | |
| bool | is_normalized (float throttle, const float min, const float max) |
| void | pose_cb (const geometry_msgs::PoseStamped::ConstPtr &req) |
| void | send_attitude_ang_velocity (const ros::Time &stamp, const Eigen::Vector3d &ang_vel) |
| Send angular velocity setpoint to FCU attitude controller. | |
| void | send_attitude_target (const ros::Time &stamp, const Eigen::Affine3d &tr) |
| Send attitude setpoint to FCU attitude controller. | |
| void | send_attitude_throttle (const float throttle) |
| Send throttle to FCU attitude controller. | |
| 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) |
| void | throttle_cb (const std_msgs::Float64::ConstPtr &req) |
| void | transform_cb (const geometry_msgs::TransformStamped &transform) |
| void | twist_cb (const geometry_msgs::TwistStamped::ConstPtr &req) |
Private Attributes | |
| ros::Subscriber | pose_sub |
| bool | reverse_throttle |
| ros::NodeHandle | sp_nh |
| std::string | tf_child_frame_id |
| std::string | tf_frame_id |
| double | tf_rate |
| ros::Subscriber | throttle_sub |
| ros::Subscriber | twist_sub |
| UAS * | uas |
Friends | |
| class | TF2ListenerMixin |
Setpoint attitude plugin.
Send setpoint attitude/orientation/thrust to FCU controller.
Definition at line 33 of file setpoint_attitude.cpp.