#include <geometry_msgs/Wrench.h>#include <boost/range/iterator_range.hpp>

Go to the source code of this file.
| Classes | |
| class | hector_quadrotor_model::PrintVector< T > | 
| Namespaces | |
| namespace | hector_quadrotor_model | 
| Functions | |
| template<typename T > | |
| static void | hector_quadrotor_model::checknan (T &value, const std::string &text="") | 
| template<typename Message , typename Quaternion > | |
| static void | hector_quadrotor_model::fromQuaternion (const Quaternion &vector, Message &msg) | 
| template<typename Message , typename Vector > | |
| static void | hector_quadrotor_model::fromVector (const Vector &vector, Message &msg) | 
| template<typename T > | |
| int | hector_quadrotor_model::isinf (const T &value) | 
| template<typename T , std::size_t N> | |
| int | hector_quadrotor_model::isinf (const boost::array< T, N > &array) | 
| template<typename IteratorT > | |
| int | hector_quadrotor_model::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) | 
| template<typename T > | |
| int | hector_quadrotor_model::isnan (const T &value) | 
| template<typename T , std::size_t N> | |
| int | hector_quadrotor_model::isnan (const boost::array< T, N > &array) | 
| template<typename IteratorT > | |
| int | hector_quadrotor_model::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) | 
| template<typename T > | |
| void | hector_quadrotor_model::limit (T &value, const T &min, const T &max) | 
| template<typename T , std::size_t N> | |
| void | hector_quadrotor_model::limit (boost::array< T, N > &array, const T &min, const T &max) | 
| template<typename IteratorT > | |
| void | hector_quadrotor_model::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) | 
| static geometry_msgs::Vector3 | hector_quadrotor_model::operator+ (const geometry_msgs::Vector3 &a, const geometry_msgs::Vector3 &b) | 
| static geometry_msgs::Wrench | hector_quadrotor_model::operator+ (const geometry_msgs::Wrench &a, const geometry_msgs::Wrench &b) | 
| template<typename T > | |
| std::ostream & | hector_quadrotor_model::operator<< (std::ostream &os, const PrintVector< T > &vector) | 
| template<typename Message , typename Quaternion > | |
| static void | hector_quadrotor_model::toQuaternion (const Message &msg, Quaternion &vector) | 
| template<typename Message , typename Vector > | |
| static void | hector_quadrotor_model::toVector (const Message &msg, Vector &vector) |