#include <quadrotor_interface.h>
Definition at line 42 of file quadrotor_interface.h.
hector_quadrotor_interface::QuadrotorInterface::QuadrotorInterface |
( |
| ) |
|
hector_quadrotor_interface::QuadrotorInterface::~QuadrotorInterface |
( |
| ) |
|
|
virtual |
template<typename HandleType >
boost::shared_ptr<HandleType> hector_quadrotor_interface::QuadrotorInterface::addInput |
( |
const std::string & |
name | ) |
|
|
inline |
template<typename HandleType >
boost::shared_ptr<HandleType> hector_quadrotor_interface::QuadrotorInterface::addOutput |
( |
const std::string & |
name | ) |
|
|
inline |
void hector_quadrotor_interface::QuadrotorInterface::disconnect |
( |
const CommandHandle * |
handle | ) |
|
bool hector_quadrotor_interface::QuadrotorInterface::enabled |
( |
const CommandHandle * |
handle | ) |
const |
template<typename HandleType >
HandleType::ValueType const* hector_quadrotor_interface::QuadrotorInterface::getCommand |
( |
const std::string & |
name | ) |
const |
|
inline |
template<typename HandleType >
boost::shared_ptr<HandleType> hector_quadrotor_interface::QuadrotorInterface::getHandle |
( |
| ) |
|
|
inline |
template<typename HandleType >
boost::shared_ptr<HandleType> hector_quadrotor_interface::QuadrotorInterface::getInput |
( |
const std::string & |
name | ) |
const |
|
inline |
const MotorCommand * hector_quadrotor_interface::QuadrotorInterface::getMotorCommand |
( |
| ) |
const |
template<typename HandleType >
boost::shared_ptr<HandleType> hector_quadrotor_interface::QuadrotorInterface::getOutput |
( |
const std::string & |
name | ) |
const |
|
inline |
PoseHandlePtr hector_quadrotor_interface::QuadrotorInterface::getPose |
( |
| ) |
|
|
inline |
const Pose * hector_quadrotor_interface::QuadrotorInterface::getPoseCommand |
( |
| ) |
const |
ImuHandlePtr hector_quadrotor_interface::QuadrotorInterface::getSensorImu |
( |
| ) |
|
|
inline |
TwistHandlePtr hector_quadrotor_interface::QuadrotorInterface::getTwist |
( |
| ) |
|
|
inline |
const Twist * hector_quadrotor_interface::QuadrotorInterface::getTwistCommand |
( |
| ) |
const |
const Wrench * hector_quadrotor_interface::QuadrotorInterface::getWrenchCommand |
( |
| ) |
const |
bool hector_quadrotor_interface::QuadrotorInterface::preempt |
( |
const CommandHandle * |
handle | ) |
|
void hector_quadrotor_interface::QuadrotorInterface::registerAccel |
( |
geometry_msgs::Accel * |
accel | ) |
|
|
inline |
void hector_quadrotor_interface::QuadrotorInterface::registerMotorStatus |
( |
hector_uav_msgs::MotorStatus * |
motor_status | ) |
|
|
inline |
void hector_quadrotor_interface::QuadrotorInterface::registerPose |
( |
geometry_msgs::Pose * |
pose | ) |
|
|
inline |
void hector_quadrotor_interface::QuadrotorInterface::registerSensorImu |
( |
sensor_msgs::Imu * |
imu | ) |
|
|
inline |
void hector_quadrotor_interface::QuadrotorInterface::registerTwist |
( |
geometry_msgs::Twist * |
twist | ) |
|
|
inline |
bool hector_quadrotor_interface::QuadrotorInterface::start |
( |
const CommandHandle * |
handle | ) |
|
bool hector_quadrotor_interface::QuadrotorInterface::stop |
( |
const CommandHandle * |
handle | ) |
|
std::map<std::string, const CommandHandle *> hector_quadrotor_interface::QuadrotorInterface::enabled_ |
|
private |
ImuHandlePtr hector_quadrotor_interface::QuadrotorInterface::imu_ |
std::map<std::string, CommandHandlePtr> hector_quadrotor_interface::QuadrotorInterface::inputs_ |
|
private |
std::map<std::string, CommandHandlePtr> hector_quadrotor_interface::QuadrotorInterface::outputs_ |
|
private |
PoseHandlePtr hector_quadrotor_interface::QuadrotorInterface::pose_ |
The documentation for this class was generated from the following files: