setpoint_attitude.cpp
Go to the documentation of this file.
1 
10 /*
11  * Copyright 2014 Nuno Marques.
12  *
13  * This file is part of the mavros package and subject to the license terms
14  * in the top-level LICENSE file of the mavros repository.
15  * https://github.com/mavlink/mavros/tree/master/LICENSE.md
16  */
17 
18 #include <mavros/mavros_plugin.h>
19 #include <mavros/setpoint_mixin.h>
21 
25 
26 #include <geometry_msgs/PoseStamped.h>
27 #include <geometry_msgs/TwistStamped.h>
28 #include <mavros_msgs/Thrust.h>
29 
30 namespace mavros {
31 namespace std_plugins {
32 
37 
44  private plugin::SetAttitudeTargetMixin<SetpointAttitudePlugin>,
45  private plugin::TF2ListenerMixin<SetpointAttitudePlugin> {
46 public:
48  sp_nh("~setpoint_attitude"),
49  tf_listen(false),
50  tf_rate(50.0),
51  use_quaternion(false),
52  reverse_thrust(false)
53  { }
54 
55  void initialize(UAS &uas_) override
56  {
57  PluginBase::initialize(uas_);
58 
59  // main params
60  sp_nh.param("use_quaternion", use_quaternion, false);
61  sp_nh.param("reverse_thrust", reverse_thrust, false);
62  // tf params
63  sp_nh.param("tf/listen", tf_listen, false);
64  sp_nh.param<std::string>("tf/frame_id", tf_frame_id, "map");
65  sp_nh.param<std::string>("tf/child_frame_id", tf_child_frame_id, "target_attitude");
66  sp_nh.param("tf/rate_limit", tf_rate, 50.0);
67 
68  // thrust msg subscriber to sync
69  th_sub.subscribe(sp_nh, "thrust", 1);
70 
71  if (tf_listen) {
72  ROS_INFO_STREAM_NAMED("attitude",
73  "Listen to desired attitude transform "
74  << tf_frame_id << " -> " << tf_child_frame_id);
75 
76  tf2_start<mavros_msgs::Thrust>("AttitudeSpTFSync", th_sub, &SetpointAttitudePlugin::transform_cb);
77  }
78  else if (use_quaternion) {
82  pose_sub.subscribe(sp_nh, "attitude", 1);
83 
89  sync_pose->registerCallback(boost::bind(&SetpointAttitudePlugin::attitude_pose_cb, this, _1, _2));
90  }
91  else {
92  twist_sub.subscribe(sp_nh, "cmd_vel", 1);
94  sync_twist->registerCallback(boost::bind(&SetpointAttitudePlugin::attitude_twist_cb, this, _1, _2));
95  }
96  }
97 
99  {
100  return { /* Rx disabled */ };
101  }
102 
103 private:
105  friend class TF2ListenerMixin;
107 
111 
112  std::unique_ptr<SyncPoseThrust> sync_pose;
113  std::unique_ptr<SyncTwistThrust> sync_twist;
114 
115  std::string tf_frame_id;
116  std::string tf_child_frame_id;
117 
118  bool tf_listen;
119  double tf_rate;
120 
122 
125 
130  inline bool is_normalized(float thrust){
131  if (reverse_thrust) {
132  if (thrust < -1.0) {
133  ROS_WARN_NAMED("attitude", "Not normalized reversed thrust! Thd(%f) < Min(%f)", thrust, -1.0);
134  return false;
135  }
136  }
137  else {
138  if (thrust < 0.0) {
139  ROS_WARN_NAMED("attitude", "Not normalized thrust! Thd(%f) < Min(%f)", thrust, 0.0);
140  return false;
141  }
142  }
143 
144  if (thrust > 1.0) {
145  ROS_WARN_NAMED("attitude", "Not normalized thrust! Thd(%f) > Max(%f)", thrust, 1.0);
146  return false;
147  }
148  return true;
149  }
150 
151  /* -*- mid-level helpers -*- */
152 
156  void send_attitude_quaternion(const ros::Time &stamp, const Eigen::Affine3d &tr, const float thrust)
157  {
161  const uint8_t ignore_all_except_q_and_thrust = (7 << 0);
162 
164  ftf::transform_orientation_baselink_aircraft(Eigen::Quaterniond(tr.rotation()))
165  );
166 
167  set_attitude_target(stamp.toNSec() / 1000000,
168  ignore_all_except_q_and_thrust,
169  q,
170  Eigen::Vector3d::Zero(),
171  thrust);
172  }
173 
177  void send_attitude_ang_velocity(const ros::Time &stamp, const Eigen::Vector3d &ang_vel, const float thrust)
178  {
182  const uint8_t ignore_all_except_rpy = (1 << 7);
183 
184  auto av = ftf::transform_frame_ned_enu(ang_vel);
185 
186  set_attitude_target(stamp.toNSec() / 1000000,
187  ignore_all_except_rpy,
188  Eigen::Quaterniond::Identity(),
189  av,
190  thrust);
191  }
192 
193  /* -*- callbacks -*- */
194 
195  void transform_cb(const geometry_msgs::TransformStamped &transform, const mavros_msgs::Thrust::ConstPtr &thrust_msg) {
196  Eigen::Affine3d tr;
197  tf::transformMsgToEigen(transform.transform, tr);
198 
199  send_attitude_quaternion(transform.header.stamp, tr, thrust_msg->thrust);
200  }
201 
203  Eigen::Affine3d tr;
204  tf::poseMsgToEigen(pose_msg->pose, tr);
205 
206  if (is_normalized(thrust_msg->thrust))
207  send_attitude_quaternion(pose_msg->header.stamp, tr, thrust_msg->thrust);
208  }
209 
211  Eigen::Vector3d ang_vel;
212  tf::vectorMsgToEigen(req->twist.angular, ang_vel);
213 
214  if (is_normalized(thrust_msg->thrust))
215  send_attitude_ang_velocity(req->header.stamp, ang_vel, thrust_msg->thrust);
216  }
217 
218 };
219 } // namespace std_plugins
220 } // namespace mavros
221 
tf::poseMsgToEigen
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
mavros::std_plugins::SetpointAttitudePlugin::reverse_thrust
bool reverse_thrust
Definition: setpoint_attitude.cpp:123
mavros::std_plugins::SyncPoseThrustPolicy
message_filters::sync_policies::ApproximateTime< geometry_msgs::PoseStamped, mavros_msgs::Thrust > SyncPoseThrustPolicy
Definition: setpoint_attitude.cpp:33
mavros::std_plugins::SetpointAttitudePlugin::SetAttitudeTargetMixin
friend class SetAttitudeTargetMixin
Definition: setpoint_attitude.cpp:104
mavros::plugin::PluginBase::Subscriptions
std::vector< HandlerInfo > Subscriptions
Subscriptions vector.
Definition: mavros_plugin.h:47
mavros::plugin::TF2ListenerMixin
This mixin adds TF2 listener thread to plugin.
Definition: setpoint_mixin.h:167
mavros::std_plugins::SetpointAttitudePlugin::is_normalized
bool is_normalized(float thrust)
Function to verify if the thrust values are normalized; considers also the reversed trust values.
Definition: setpoint_attitude.cpp:130
message_filters::Synchronizer
mavros::std_plugins::SetpointAttitudePlugin::sync_pose
std::unique_ptr< SyncPoseThrust > sync_pose
Definition: setpoint_attitude.cpp:112
mavros::plugin::PluginBase::PluginBase
PluginBase()
Plugin constructor Should not do anything before initialize()
Definition: mavros_plugin.h:74
mavros::UAS
UAS for plugins.
Definition: mavros_uas.h:67
mavros::std_plugins::SetpointAttitudePlugin::th_sub
message_filters::Subscriber< mavros_msgs::Thrust > th_sub
Definition: setpoint_attitude.cpp:108
mavros::std_plugins::SetpointAttitudePlugin::initialize
void initialize(UAS &uas_) override
Plugin initializer.
Definition: setpoint_attitude.cpp:55
ConstPtr
std::shared_ptr< MAVConnInterface const > ConstPtr
mavros::plugin::SetAttitudeTargetMixin< SetpointAttitudePlugin >::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.
Definition: setpoint_mixin.h:130
mavros::std_plugins::SyncPoseThrust
message_filters::Synchronizer< SyncPoseThrustPolicy > SyncPoseThrust
Definition: setpoint_attitude.cpp:35
mavros::std_plugins::SetpointAttitudePlugin::get_subscriptions
Subscriptions get_subscriptions() override
Return vector of MAVLink message subscriptions (handlers)
Definition: setpoint_attitude.cpp:98
mavros::std_plugins::SetpointAttitudePlugin::transform_cb
void transform_cb(const geometry_msgs::TransformStamped &transform, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
Definition: setpoint_attitude.cpp:195
mavros::std_plugins::SetpointAttitudePlugin::sp_nh
ros::NodeHandle sp_nh
Definition: setpoint_attitude.cpp:106
mavros::std_plugins::SetpointAttitudePlugin
Setpoint attitude plugin.
Definition: setpoint_attitude.cpp:43
mavros::std_plugins::SetpointAttitudePlugin::pose_sub
message_filters::Subscriber< geometry_msgs::PoseStamped > pose_sub
Definition: setpoint_attitude.cpp:109
mavros::std_plugins::SetpointAttitudePlugin::normalized_thrust
float normalized_thrust
Definition: setpoint_attitude.cpp:124
message_filters::Subscriber< mavros_msgs::Thrust >
mavros::std_plugins::SetpointAttitudePlugin::tf_frame_id
std::string tf_frame_id
Definition: setpoint_attitude.cpp:115
message_filters::sync_policies::ApproximateTime
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
mavros::std_plugins::SetpointAttitudePlugin::use_quaternion
bool use_quaternion
Definition: setpoint_attitude.cpp:121
mavros::std_plugins::SetpointAttitudePlugin::attitude_pose_cb
void attitude_pose_cb(const geometry_msgs::PoseStamped::ConstPtr &pose_msg, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
Definition: setpoint_attitude.cpp:202
mavros::std_plugins::SetpointAttitudePlugin::twist_sub
message_filters::Subscriber< geometry_msgs::TwistStamped > twist_sub
Definition: setpoint_attitude.cpp:110
mavros::std_plugins::SyncTwistThrustPolicy
message_filters::sync_policies::ApproximateTime< geometry_msgs::TwistStamped, mavros_msgs::Thrust > SyncTwistThrustPolicy
Definition: setpoint_attitude.cpp:34
subscriber.h
eigen_msg.h
tf::vectorMsgToEigen
void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
mavros::ftf::transform_orientation_baselink_aircraft
T transform_orientation_baselink_aircraft(const T &in)
Transform from attitude represented WRT baselink frame to attitude represented WRT body frame.
Definition: frame_tf.h:187
tf::transformMsgToEigen
void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e)
setpoint_mixin.h
Mixin for setpoint plugins.
mavros_plugin.h
MAVROS Plugin base.
mavros::std_plugins::SetpointAttitudePlugin::tf_child_frame_id
std::string tf_child_frame_id
Definition: setpoint_attitude.cpp:116
message_filters::Subscriber::subscribe
void subscribe()
mavros::std_plugins::SetpointAttitudePlugin::tf_listen
bool tf_listen
Definition: setpoint_attitude.cpp:118
mavros
Definition: frame_tf.h:34
mavros::ftf::transform_orientation_enu_ned
T transform_orientation_enu_ned(const T &in)
Transform from attitude represented WRT ENU frame to attitude represented WRT NED frame.
Definition: frame_tf.h:169
mavros::std_plugins::SetpointAttitudePlugin::send_attitude_ang_velocity
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.
Definition: setpoint_attitude.cpp:177
ros::Time
mavros::std_plugins::SetpointAttitudePlugin::attitude_twist_cb
void attitude_twist_cb(const geometry_msgs::TwistStamped::ConstPtr &req, const mavros_msgs::Thrust::ConstPtr &thrust_msg)
Definition: setpoint_attitude.cpp:210
mavros::plugin::PluginBase
MAVROS Plugin base class.
Definition: mavros_plugin.h:36
class_list_macros.hpp
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
synchronizer.h
mavros::std_plugins::SetpointAttitudePlugin::tf_rate
double tf_rate
Definition: setpoint_attitude.cpp:119
approximate_time.h
mavros::std_plugins::SetpointAttitudePlugin::TF2ListenerMixin
friend class TF2ListenerMixin
Definition: setpoint_attitude.cpp:105
mavros::std_plugins::SyncTwistThrust
message_filters::Synchronizer< SyncTwistThrustPolicy > SyncTwistThrust
Definition: setpoint_attitude.cpp:36
mavros::ftf::transform_frame_ned_enu
T transform_frame_ned_enu(const T &in)
Transform data expressed in NED to ENU frame.
Definition: frame_tf.h:215
mavros::plugin::SetAttitudeTargetMixin
This mixin adds set_attitude_target()
Definition: setpoint_mixin.h:127
mavros::std_plugins::SetpointAttitudePlugin::send_attitude_quaternion
void send_attitude_quaternion(const ros::Time &stamp, const Eigen::Affine3d &tr, const float thrust)
Send attitude setpoint and thrust to FCU attitude controller.
Definition: setpoint_attitude.cpp:156
ros::NodeHandle
mavros::std_plugins::SetpointAttitudePlugin::SetpointAttitudePlugin
SetpointAttitudePlugin()
Definition: setpoint_attitude.cpp:47
mavros::std_plugins::SetpointAttitudePlugin::sync_twist
std::unique_ptr< SyncTwistThrust > sync_twist
Definition: setpoint_attitude.cpp:113


mavros
Author(s): Vladimir Ermakov
autogenerated on Tue May 6 2025 02:34:03