#include <limiters.h>
|
void | init (const ros::NodeHandle &nh, const std::string &field=std::string()) |
|
AttitudeCommand | limit (const AttitudeCommand &input) |
|
AttitudeCommand | operator() (const AttitudeCommand &input) |
|
Definition at line 207 of file limiters.h.
void hector_quadrotor_interface::AttitudeCommandLimiter::init |
( |
const ros::NodeHandle & |
nh, |
|
|
const std::string & |
field = std::string() |
|
) |
| |
|
inline |
AttitudeCommand hector_quadrotor_interface::AttitudeCommandLimiter::limit |
( |
const AttitudeCommand & |
input | ) |
|
|
inline |
AttitudeCommand hector_quadrotor_interface::AttitudeCommandLimiter::operator() |
( |
const AttitudeCommand & |
input | ) |
|
|
inline |
double hector_quadrotor_interface::AttitudeCommandLimiter::absolute_max |
FieldLimiter<double> hector_quadrotor_interface::AttitudeCommandLimiter::pitch |
FieldLimiter<double> hector_quadrotor_interface::AttitudeCommandLimiter::roll |
The documentation for this class was generated from the following file: