Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #ifndef ROTORS_GAZEBO_PLUGINS_COMMON_H_
00023 #define ROTORS_GAZEBO_PLUGINS_COMMON_H_
00024
00025 #include <Eigen/Dense>
00026 #include <gazebo/gazebo.hh>
00027
00028 namespace gazebo {
00029
00030
00031
00032
00033
00036
00037
00038
00039
00040 static const bool kPrintOnPluginLoad = false;
00041 static const bool kPrintOnUpdates = false;
00042 static const bool kPrintOnMsgCallback = false;
00043
00045
00046
00047 static const std::string kDefaultNamespace = "";
00048 static constexpr double kDefaultRotorVelocitySlowdownSim = 10.0;
00049
00050
00051
00052
00053
00054
00055 static const std::string kConnectGazeboToRosSubtopic = "connect_gazebo_to_ros_subtopic";
00056 static const std::string kConnectRosToGazeboSubtopic = "connect_ros_to_gazebo_subtopic";
00057
00060 static const std::string kBroadcastTransformSubtopic = "broadcast_transform";
00061
00062
00069 template<class T>
00070 bool getSdfParam(sdf::ElementPtr sdf, const std::string& name, T& param, const T& default_value, const bool& verbose =
00071 false) {
00072 if (sdf->HasElement(name)) {
00073 param = sdf->GetElement(name)->Get<T>();
00074 return true;
00075 }
00076 else {
00077 param = default_value;
00078 if (verbose)
00079 gzerr << "[rotors_gazebo_plugins] Please specify a value for parameter \"" << name << "\".\n";
00080 }
00081 return false;
00082 }
00083
00084 }
00085
00096 template <typename T>
00097 class FirstOrderFilter {
00098
00099 public:
00100 FirstOrderFilter(double timeConstantUp, double timeConstantDown, T initialState):
00101 timeConstantUp_(timeConstantUp),
00102 timeConstantDown_(timeConstantDown),
00103 previousState_(initialState) {}
00104
00106 T updateFilter(T inputState, double samplingTime) {
00107
00108 T outputState;
00109 if (inputState > previousState_) {
00110
00111 double alphaUp = exp(-samplingTime / timeConstantUp_);
00112
00113 outputState = alphaUp * previousState_ + (1 - alphaUp) * inputState;
00114
00115 }
00116 else {
00117
00118 double alphaDown = exp(-samplingTime / timeConstantDown_);
00119 outputState = alphaDown * previousState_ + (1 - alphaDown) * inputState;
00120 }
00121 previousState_ = outputState;
00122 return outputState;
00123
00124 }
00125
00126 ~FirstOrderFilter() {}
00127
00128 protected:
00129 double timeConstantUp_;
00130 double timeConstantDown_;
00131 T previousState_;
00132 };
00133
00135 template<class Derived>
00136 Eigen::Quaternion<typename Derived::Scalar> QuaternionFromSmallAngle(const Eigen::MatrixBase<Derived> & theta) {
00137 typedef typename Derived::Scalar Scalar;
00138 EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived);
00139 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 3);
00140 const Scalar q_squared = theta.squaredNorm() / 4.0;
00141
00142 if (q_squared < 1) {
00143 return Eigen::Quaternion<Scalar>(sqrt(1 - q_squared), theta[0] * 0.5, theta[1] * 0.5, theta[2] * 0.5);
00144 }
00145 else {
00146 const Scalar w = 1.0 / sqrt(1 + q_squared);
00147 const Scalar f = w * 0.5;
00148 return Eigen::Quaternion<Scalar>(w, theta[0] * f, theta[1] * f, theta[2] * f);
00149 }
00150 }
00151
00152 template<class In, class Out>
00153 void copyPosition(const In& in, Out* out) {
00154 out->x = in.x;
00155 out->y = in.y;
00156 out->z = in.z;
00157 }
00158
00159 #endif
rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:43