29 #ifndef HECTOR_QUADROTOR_INTERFACE_QUADROTOR_INTERFACE_H 30 #define HECTOR_QUADROTOR_INTERFACE_QUADROTOR_INTERFACE_H 100 template<
typename HandleType>
106 template<
typename HandleType>
110 if (input) {
return input; }
113 input.reset(
new HandleType(
this, name));
120 if (output) output->connectTo(*input);
126 template<
typename HandleType>
130 if (output) {
return output; }
133 output.reset(
new HandleType(
this, name));
135 *output = output->ownData(
new typename HandleType::ValueType());
144 if (input) output->connectTo(*input);
150 template<
typename HandleType>
154 return boost::dynamic_pointer_cast<HandleType>(
outputs_.at(name));
157 template<
typename HandleType>
161 return boost::dynamic_pointer_cast<HandleType>(
inputs_.at(name));
164 template<
typename HandleType>
165 typename HandleType::ValueType
const *
getCommand(
const std::string &name)
const 168 if (!output || !output->connected())
170 return &(output->command());
186 std::map<std::string, CommandHandlePtr>
inputs_;
188 std::map<std::string, const CommandHandle *>
enabled_;
193 #endif // HECTOR_QUADROTOR_INTERFACE_QUADROTOR_INTERFACE_H boost::shared_ptr< TwistHandle > TwistHandlePtr
boost::shared_ptr< HandleType > getOutput(const std::string &name) const
void registerPose(geometry_msgs::Pose *pose)
boost::shared_ptr< ImuHandle > ImuHandlePtr
void registerMotorStatus(hector_uav_msgs::MotorStatus *motor_status)
boost::shared_ptr< HandleType > addInput(const std::string &name)
boost::shared_ptr< AccelerationHandle > AccelerationHandlePtr
virtual ~QuadrotorInterface()
bool start(const CommandHandle *handle)
void disconnect(const CommandHandle *handle)
bool stop(const CommandHandle *handle)
boost::shared_ptr< HandleType > getInput(const std::string &name) const
virtual void claim(std::string resource)
AccelerationHandlePtr accel_
const Pose * getPoseCommand() const
std::map< std::string, CommandHandlePtr > outputs_
const Wrench * getWrenchCommand() const
HandleType::ValueType const * getCommand(const std::string &name) const
boost::shared_ptr< HandleType > addOutput(const std::string &name)
boost::shared_ptr< HandleType > getHandle()
bool enabled(const CommandHandle *handle) const
MotorStatusHandlePtr motor_status_
ImuHandlePtr getSensorImu()
void registerTwist(geometry_msgs::Twist *twist)
bool preempt(const CommandHandle *handle)
std::map< std::string, const CommandHandle * > enabled_
void registerAccel(geometry_msgs::Accel *accel)
void registerSensorImu(sensor_msgs::Imu *imu)
const Twist * getTwistCommand() const
MotorStatusHandlePtr getMotorStatus()
const MotorCommand * getMotorCommand() const
boost::shared_ptr< MotorStatusHandle > MotorStatusHandlePtr
boost::shared_ptr< PoseHandle > PoseHandlePtr
std::map< std::string, CommandHandlePtr > inputs_
AccelerationHandlePtr getAccel()
TwistHandlePtr getTwist()