#include <telekyb_defines/telekyb_defines.hpp>
#include <tk_trajctrl/TrajectoryTracker.hpp>
#include <pluginlib/class_loader.h>
#include <tk_param_estimator/MassEstimator.hpp>
#include <tk_param_estimator/InertiaMatrixEstimator.hpp>
#include <ros/ros.h>
#include <telekyb_base/Options.hpp>
#include <telekyb_base/Time.hpp>
#include <boost/thread/mutex.hpp>
Go to the source code of this file.
Functions | |
TELEKYB_ENUM_VALUES (SaturationType, const char *,(none)("No command saturation applied")(uniform)("Uniform command saturation")(qp)("Quadratic programming command saturation")) namespace TELEKYB_NAMESPACE |
TELEKYB_ENUM_VALUES | ( | SaturationType | , |
const char * | , | ||
(none)("No command saturation applied")(uniform)("Uniform command saturation")(qp)("Quadratic programming command saturation") | |||
) |
Computes the hat map
Returns the 3D skew-symmetric matrix corresponding to the input 3D vector
Computes the vee map
Returns the 3D vector corresponding to the input 3D skew-symmetric matrix
Definition at line 35 of file SMURFTrajectoryTracker.hpp.