26 #include <geometry_msgs/PoseStamped.h> 27 #include <geometry_msgs/TwistStamped.h> 28 #include <mavros_msgs/Thrust.h> 31 namespace std_plugins {
48 sp_nh(
"~setpoint_attitude"),
57 PluginBase::initialize(uas_);
73 "Listen to desired attitude transform " 74 << tf_frame_id <<
" -> " << tf_child_frame_id);
131 if (reverse_thrust) {
133 ROS_WARN_NAMED(
"attitude",
"Not normalized reversed thrust! Thd(%f) < Min(%f)", thrust, -1.0);
139 ROS_WARN_NAMED(
"attitude",
"Not normalized thrust! Thd(%f) < Min(%f)", thrust, 0.0);
145 ROS_WARN_NAMED(
"attitude",
"Not normalized thrust! Thd(%f) > Max(%f)", thrust, 1.0);
161 const uint8_t ignore_all_except_q_and_thrust = (7 << 0);
168 ignore_all_except_q_and_thrust,
170 Eigen::Vector3d::Zero(),
182 const uint8_t ignore_all_except_rpy = (1 << 7);
187 ignore_all_except_rpy,
188 Eigen::Quaterniond::Identity(),
211 Eigen::Vector3d ang_vel;
MAVROS Plugin base class.
std::shared_ptr< MAVConnInterface const > ConstPtr
message_filters::Subscriber< geometry_msgs::PoseStamped > pose_sub
Subscriptions get_subscriptions()
Return vector of MAVLink message subscriptions (handlers)
#define ROS_WARN_NAMED(name,...)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
message_filters::sync_policies::ApproximateTime< geometry_msgs::PoseStamped, mavros_msgs::Thrust > SyncPoseThrustPolicy
friend class SetAttitudeTargetMixin
This mixin adds TF2 listener thread to plugin.
message_filters::sync_policies::ApproximateTime< geometry_msgs::TwistStamped, mavros_msgs::Thrust > SyncTwistThrustPolicy
#define ROS_INFO_STREAM_NAMED(name, args)
message_filters::Subscriber< mavros_msgs::Thrust > th_sub
T transform_orientation_enu_ned(const T &in)
Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame...
message_filters::Synchronizer< SyncTwistThrustPolicy > SyncTwistThrust
PluginBase()
Plugin constructor Should not do anything before initialize()
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
message_filters::Synchronizer< SyncPoseThrustPolicy > SyncPoseThrust
friend class TF2ListenerMixin
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Mixin for setpoint plugins.
Setpoint attitude plugin.
void send_attitude_ang_velocity(const ros::Time &stamp, const Eigen::Vector3d &ang_vel, const float thrust)
Send angular velocity setpoint and thrust to FCU attitude controller.
T transform_frame_ned_enu(const T &in)
Transform data expressed in NED to ENU frame.
std::unique_ptr< SyncTwistThrust > sync_twist
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< geometry_msgs::TwistStamped > twist_sub
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
This mixin adds set_attitude_target()
void set_attitude_target(uint32_t time_boot_ms, uint8_t type_mask, Eigen::Quaterniond orientation, Eigen::Vector3d body_rate, float thrust)
Message sepecification: https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET.
bool is_normalized(float thrust)
Function to verify if the thrust values are normalized; considers also the reversed trust values...
void send_attitude_quaternion(const ros::Time &stamp, const Eigen::Affine3d &tr, const float thrust)
Send attitude setpoint and thrust to FCU attitude controller.
T transform_orientation_baselink_aircraft(const T &in)
Transform from attitude represented WRT baselink frame to attitude represented WRT body frame...
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void attitude_pose_cb(const geometry_msgs::PoseStamped::ConstPtr &pose_msg, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
void initialize(UAS &uas_)
Plugin initializer.
void transform_cb(const geometry_msgs::TransformStamped &transform, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
std::string tf_child_frame_id
void attitude_twist_cb(const geometry_msgs::TwistStamped::ConstPtr &req, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
std::unique_ptr< SyncPoseThrust > sync_pose