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
00023
00024
00025
00026
00027
00028
00029 #ifndef HECTOR_QUADROTOR_MODEL_HELPERS_H
00030 #define HECTOR_QUADROTOR_MODEL_HELPERS_H
00031
00032 #include <geometry_msgs/Wrench.h>
00033 #include <boost/range/iterator_range.hpp>
00034
00035 namespace hector_quadrotor_model
00036 {
00037
00038 template <typename T> int isnan(const T& value) {
00039 return std::isnan(value);
00040 }
00041
00042 template <typename T, std::size_t N> int isnan(const boost::array<T,N>& array) {
00043 for(typename boost::array<T,N>::const_iterator it = array.begin(); it != array.end(); ++it)
00044 if (std::isnan(*it)) return std::isnan(*it);
00045 return false;
00046 }
00047
00048 template <typename IteratorT> int isnan(const boost::iterator_range<IteratorT>& range, const typename boost::iterator_range<IteratorT>::value_type& min, const typename boost::iterator_range<IteratorT>::value_type& max) {
00049 for(IteratorT it = range.begin(); it != range.end(); ++it)
00050 if (std::isnan(*it)) return std::isnan(*it);
00051 return false;
00052 }
00053
00054 template <typename T> int isinf(const T& value) {
00055 return std::isinf(value);
00056 }
00057
00058 template <typename T, std::size_t N> int isinf(const boost::array<T,N>& array) {
00059 for(typename boost::array<T,N>::const_iterator it = array.begin(); it != array.end(); ++it)
00060 if (std::isinf(*it)) return std::isinf(*it);
00061 return false;
00062 }
00063
00064 template <typename IteratorT> int isinf(const boost::iterator_range<IteratorT>& range, const typename boost::iterator_range<IteratorT>::value_type& min, const typename boost::iterator_range<IteratorT>::value_type& max) {
00065 for(IteratorT it = range.begin(); it != range.end(); ++it)
00066 if (std::isinf(*it)) return std::isinf(*it);
00067 return false;
00068 }
00069
00070 template <typename T> void limit(T& value, const T& min, const T& max) {
00071 if (!isnan(min) && value < min) value = min;
00072 if (!isnan(max) && value > max) value = max;
00073 }
00074
00075 template <typename T, std::size_t N> void limit(boost::array<T,N>& array, const T& min, const T& max) {
00076 for(typename boost::array<T,N>::iterator it = array.begin(); it != array.end(); ++it)
00077 limit(*it, min, max);
00078 }
00079
00080 template <typename IteratorT> void limit(const boost::iterator_range<IteratorT>& range, const typename boost::iterator_range<IteratorT>::value_type& min, const typename boost::iterator_range<IteratorT>::value_type& max) {
00081 for(IteratorT it = range.begin(); it != range.end(); ++it)
00082 limit(*it, min, max);
00083 }
00084
00085 template <typename T> static inline void checknan(T& value, const std::string& text = "") {
00086 if (isnan(value)) {
00087 #ifndef NDEBUG
00088 if (!text.empty()) std::cerr << text << " contains **!?* Nan values!" << std::endl;
00089 #endif
00090 value = T();
00091 return;
00092 }
00093
00094 if (isinf(value)) {
00095 #ifndef NDEBUG
00096 if (!text.empty()) std::cerr << text << " is +-Inf!" << std::endl;
00097 #endif
00098 value = T();
00099 return;
00100 }
00101 }
00102
00103 template <typename Message, typename Vector> static inline void toVector(const Message& msg, Vector& vector)
00104 {
00105 vector.x = msg.x;
00106 vector.y = msg.y;
00107 vector.z = msg.z;
00108 }
00109
00110 template <typename Message, typename Vector> static inline void fromVector(const Vector& vector, Message& msg)
00111 {
00112 msg.x = vector.x;
00113 msg.y = vector.y;
00114 msg.z = vector.z;
00115 }
00116
00117 template <typename Message, typename Quaternion> static inline void toQuaternion(const Message& msg, Quaternion& vector)
00118 {
00119 vector.w = msg.w;
00120 vector.x = msg.x;
00121 vector.y = msg.y;
00122 vector.z = msg.z;
00123 }
00124
00125 template <typename Message, typename Quaternion> static inline void fromQuaternion(const Quaternion& vector, Message& msg)
00126 {
00127 msg.w = vector.w;
00128 msg.x = vector.x;
00129 msg.y = vector.y;
00130 msg.z = vector.z;
00131 }
00132
00133 static inline geometry_msgs::Vector3 operator+(const geometry_msgs::Vector3& a, const geometry_msgs::Vector3& b)
00134 {
00135 geometry_msgs::Vector3 result;
00136 result.x = a.x + b.x;
00137 result.y = a.y + b.y;
00138 result.z = a.z + b.z;
00139 return result;
00140 }
00141
00142 static inline geometry_msgs::Wrench operator+(const geometry_msgs::Wrench& a, const geometry_msgs::Wrench& b)
00143 {
00144 geometry_msgs::Wrench result;
00145 result.force = a.force + b.force;
00146 result.torque = a.torque + b.torque;
00147 return result;
00148 }
00149
00150 template<typename T>
00151 class PrintVector {
00152 public:
00153 typedef const T* const_iterator;
00154 PrintVector(const_iterator begin, const_iterator end, const std::string &delimiter = "[ ]") : begin_(begin), end_(end), delimiter_(delimiter) {}
00155 const_iterator begin() const { return begin_; }
00156 const_iterator end() const { return end_; }
00157 std::size_t size() const { return end_ - begin_; }
00158
00159 std::ostream& operator>>(std::ostream& os) const {
00160 if (!delimiter_.empty()) os << delimiter_.substr(0, delimiter_.size() - 1);
00161 for(const_iterator it = begin(); it != end(); ++it) {
00162 if (it != begin()) os << " ";
00163 os << *it;
00164 }
00165 if (!delimiter_.empty()) os << delimiter_.substr(1, delimiter_.size() - 1);
00166 return os;
00167 }
00168
00169 private:
00170 const_iterator begin_, end_;
00171 std::string delimiter_;
00172 };
00173 template <typename T> std::ostream &operator<<(std::ostream& os, const PrintVector<T>& vector) { return vector >> os; }
00174
00175 }
00176
00177 #endif // HECTOR_QUADROTOR_MODEL_HELPERS_H