handles.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012-2016, Institute of Flight Systems and Automatic Control,
3 // Technische Universität Darmstadt.
4 // All rights reserved.
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of hector_quadrotor nor the names of its contributors
14 // may be used to endorse or promote products derived from this software
15 // without specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_QUADROTOR_INTERFACE_HANDLES_H
30 #define HECTOR_QUADROTOR_INTERFACE_HANDLES_H
31 
32 #include <geometry_msgs/Pose.h>
33 #include <geometry_msgs/Twist.h>
34 #include <geometry_msgs/Accel.h>
35 #include <geometry_msgs/Wrench.h>
36 #include <sensor_msgs/Imu.h>
37 #include <hector_uav_msgs/MotorStatus.h>
38 #include <hector_uav_msgs/MotorCommand.h>
39 #include <hector_uav_msgs/AttitudeCommand.h>
40 #include <hector_uav_msgs/YawrateCommand.h>
41 #include <hector_uav_msgs/ThrustCommand.h>
42 
44 
45 class QuadrotorInterface;
46 
47 using geometry_msgs::Pose;
48 using geometry_msgs::Point;
49 using geometry_msgs::Quaternion;
50 using geometry_msgs::Accel;
51 using geometry_msgs::Twist;
52 using geometry_msgs::Vector3;
53 using geometry_msgs::Wrench;
54 using sensor_msgs::Imu;
55 using hector_uav_msgs::MotorStatus;
56 using hector_uav_msgs::MotorCommand;
57 using hector_uav_msgs::AttitudeCommand;
58 using hector_uav_msgs::YawrateCommand;
59 using hector_uav_msgs::ThrustCommand;
60 
61 template <class Derived, typename T>
62 class Handle_
63 {
64 public:
65  typedef T ValueType;
67 
68  Handle_(const std::string& name, const std::string& field = std::string()) : interface_(0), name_(name), field_(field), value_(0) {}
69  Handle_(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : interface_(interface), name_(name), field_(field), value_(0) {}
70  Handle_(QuadrotorInterface *interface, const ValueType *source, const std::string& name, const std::string& field = std::string()) : interface_(interface), name_(name), field_(field) { *this = source; }
71  virtual ~Handle_() {}
72 
73  virtual const std::string& getName() const { return name_; }
74  virtual const std::string& getField() const { return field_; }
75 
76  virtual bool connected() const { return get(); }
77  virtual void reset() { value_ = 0; }
78 
79  Derived& operator=(const ValueType *source) { value_ = source; return static_cast<Derived &>(*this); }
80  const ValueType *get() const { return value_; }
81  const ValueType &operator*() const { return *value_; }
82 
83 protected:
85  const std::string name_;
86  const std::string field_;
87  const ValueType *value_;
88 };
89 
90 class PoseHandle : public Handle_<PoseHandle, Pose>
91 {
92 public:
93  using Base::operator=;
94 
95  PoseHandle() : Base("pose") {}
96  PoseHandle(QuadrotorInterface *interface) : Base(interface, "pose") {}
97  PoseHandle(QuadrotorInterface *interface, const Pose *pose) : Base(interface, pose, "pose") {}
98  virtual ~PoseHandle() {}
99 
100  const ValueType& pose() const { return *get(); }
101 
102  void getEulerRPY(double &roll, double &pitch, double &yaw) const;
103  double getYaw() const;
104  Vector3 toBody(const Vector3& nav) const;
105  Vector3 fromBody(const Vector3& nav) const;
106 };
108 
109 class TwistHandle : public Handle_<TwistHandle, Twist>
110 {
111 public:
112  using Base::operator=;
113 
114  TwistHandle() : Base("twist") {}
115  TwistHandle(QuadrotorInterface *interface) : Base(interface, "twist") {}
116  TwistHandle(QuadrotorInterface *interface, const Twist *twist) : Base(interface, twist, "twist") {}
117  virtual ~TwistHandle() {}
118 
119  const ValueType& twist() const { return *get(); }
120 };
122 
123 class AccelerationHandle : public Handle_<AccelerationHandle, Accel>
124 {
125 public:
126  using Base::operator=;
127 
128  AccelerationHandle() : Base("acceleration") {}
129  AccelerationHandle(QuadrotorInterface *interface) : Base(interface, "acceleration") {}
130  AccelerationHandle(QuadrotorInterface *interface, const Accel *acceleration) : Base(interface, acceleration, "acceleration") {}
131  virtual ~AccelerationHandle() {}
132 
133  const ValueType& acceleration() const { return *get(); }
134 };
136 
137 class StateHandle : public PoseHandle, public TwistHandle
138 {
139 public:
141  StateHandle(QuadrotorInterface *interface, const Pose *pose, const Twist *twist) : PoseHandle(interface, pose), TwistHandle(interface, twist) {}
142  virtual ~StateHandle() {}
143 
144  virtual bool connected() const { return PoseHandle::connected() && TwistHandle::connected(); }
145 };
147 
148 class ImuHandle : public Handle_<ImuHandle, Imu>
149 {
150 public:
151  using Base::operator=;
152 
153  ImuHandle() : Base("imu") {}
154  ImuHandle(QuadrotorInterface *interface, const Imu *imu) : Base(interface, imu, "imu") {}
155  virtual ~ImuHandle() {}
156 
157  const ValueType& imu() const { return *get(); }
158 };
160 
161 class MotorStatusHandle : public Handle_<MotorStatusHandle, MotorStatus>
162 {
163 public:
164  using Base::operator=;
165 
166  MotorStatusHandle() : Base("motor_status") {}
167  MotorStatusHandle(QuadrotorInterface *interface, const MotorStatus *motor_status) : Base(interface, motor_status, "motor_status") {}
168  virtual ~MotorStatusHandle() {}
169 
170  const ValueType& motorStatus() const { return *get(); }
171 };
173 
175 {
176 public:
177  CommandHandle() : interface_(0), preempted_(false), new_value_(false) {}
178  CommandHandle(QuadrotorInterface *interface, const std::string& name, const std::string& field) : interface_(interface), name_(name), field_(field), preempted_(false), new_value_(false) {}
179  virtual ~CommandHandle() {}
180 
181  virtual const std::string& getName() const { return name_; }
182  virtual const std::string& getField() const { return field_; }
183  virtual bool connected() const = 0;
184  virtual void reset() {}
185 
186  void *get() const { return 0; }
187 
188  bool enabled();
189  bool start();
190  void stop();
191  void disconnect();
192 
193  bool preempt();
194  void setPreempted();
195  bool preempted();
196 
197  template <typename T> T* ownData(T* data) { my_.reset(data); return data; }
198 
199  template <typename Derived> bool connectFrom(const Derived& output) {
200  Derived *me = dynamic_cast<Derived *>(this);
201  if (!me) return false;
202  ROS_DEBUG("Connected output port '%s (%p)' to input port '%s (%p)'", output.getName().c_str(), &output, me->getName().c_str(), me);
203  return (*me = output.get()).connected();
204  }
205 
206  template <typename Derived> bool connectTo(Derived& input) const {
207  const Derived *me = dynamic_cast<const Derived *>(this);
208  if (!me) return false;
209  ROS_DEBUG("Connected output port '%s (%p)' to input port '%s (%p)'", me->getName().c_str(), me, input.getName().c_str(), &input);
210  return (input = me->get()).connected();
211  }
212 
213 private:
215  const std::string name_;
216  const std::string field_;
218 
220 
221 protected:
222  mutable bool new_value_;
223  bool wasNew() const { bool old = new_value_; new_value_ = false; return old; }
224 };
226 
227 namespace internal {
228  template <class Derived> struct FieldAccessor {
229  static typename Derived::ValueType *get(void *) { return 0; }
230  };
231 }
232 
233 template <class Derived, typename T, class Parent = CommandHandle>
234 class CommandHandle_ : public Parent
235 {
236 public:
237  typedef T ValueType;
239 
240  CommandHandle_() : command_(0) {}
241  CommandHandle_(const Parent &other) : Parent(other), command_(0) {}
242  CommandHandle_(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : Parent(interface, name, field), command_(0) {}
243  virtual ~CommandHandle_() {}
244 
245  virtual bool connected() const { return get(); }
246  virtual void reset() { command_ = 0; Parent::reset(); }
247 
248  using Parent::operator=;
249  Derived& operator=(ValueType *source) { command_ = source; return static_cast<Derived &>(*this); }
250  ValueType *get() const { return command_ ? command_ : internal::FieldAccessor<Derived>::get(Parent::get()); }
251  ValueType &operator*() const { return *command_; }
252 
253  ValueType& command() { return *get(); }
254  const ValueType& getCommand() const { this->new_value_ = false; return *get(); }
255  void setCommand(const ValueType& command) { this->new_value_ = true; *get() = command; }
256  bool getCommand(ValueType& command) const { command = *getCommand(); return this->wasNew(); }
257 
258  bool update(ValueType& command) const {
259  if (!connected()) return false;
260  command = getCommand();
261  return true;
262  }
263 
264 protected:
265  ValueType *command_;
266 };
267 
268 class PoseCommandHandle : public CommandHandle_<PoseCommandHandle, Pose>
269 {
270 public:
271  using Base::operator=;
272 
274  PoseCommandHandle(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : Base(interface, name, field) {}
275  PoseCommandHandle(Pose* command) { *this = command; }
276  virtual ~PoseCommandHandle() {}
277 };
279 
280 class HorizontalPositionCommandHandle : public CommandHandle_<HorizontalPositionCommandHandle, Point, PoseCommandHandle>
281 {
282 public:
283  using Base::operator=;
284 
286  HorizontalPositionCommandHandle(const PoseCommandHandle& other) : Base(other) {}
287  HorizontalPositionCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "position.xy") {}
288  HorizontalPositionCommandHandle(Point* command) { *this = command; }
290 
291  using Base::getCommand;
292  virtual bool getCommand(double &x, double &y) const {
293  x = get()->x;
294  y = get()->y;
295  return wasNew();
296  }
297 
298  using Base::setCommand;
299  virtual void setCommand(double x, double y)
300  {
301  this->new_value_ = true;
302  get()->x = x;
303  get()->y = y;
304  }
305 
306  using Base::update;
307  bool update(Pose& command) const {
308  if (!connected()) return false;
309  getCommand(command.position.x, command.position.y);
310  return true;
311  }
312 
313  void getError(const PoseHandle &pose, double &x, double &y) const;
314 };
316 
317 namespace internal {
319  static Point *get(Pose *pose) { return &(pose->position); }
320  };
321 }
322 
323 class HeightCommandHandle : public CommandHandle_<HeightCommandHandle, double, PoseCommandHandle>
324 {
325 public:
326  using Base::operator=;
327 
329  HeightCommandHandle(const PoseCommandHandle& other) : Base(other) {}
330  HeightCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "position.z") {}
331  HeightCommandHandle(double *command) { *this = command; }
332  virtual ~HeightCommandHandle() {}
333 
334  using Base::update;
335  bool update(Pose& command) const {
336  if (!connected()) return false;
337  command.position.z = getCommand();
338  return true;
339  }
340 
341  double getError(const PoseHandle &pose) const;
342 };
344 
345 namespace internal {
346  template <> struct FieldAccessor<HeightCommandHandle> {
347  static double *get(Pose *pose) { return &(pose->position.z); }
348  };
349 }
350 
351 class HeadingCommandHandle : public CommandHandle_<HeadingCommandHandle, Quaternion, PoseCommandHandle>
352 {
353 public:
354  using Base::operator=;
355 
357  HeadingCommandHandle(const PoseCommandHandle& other) : Base(other), scalar_(0) {}
358  HeadingCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "orientation.yaw"), scalar_(0) {}
359  HeadingCommandHandle(Quaternion *command) { *this = command; }
361 
362  using Base::getCommand;
363  double getCommand() const;
364 
365  using Base::setCommand;
366  void setCommand(double command);
367 
368  using Base::update;
369  bool update(Pose& command) const;
370 
371  double getError(const PoseHandle &pose) const;
372 
373 protected:
374  double *scalar_;
375 };
377 
378 namespace internal {
379  template <> struct FieldAccessor<HeadingCommandHandle> {
380  static Quaternion *get(Pose *pose) { return &(pose->orientation); }
381  };
382 }
383 
384 class TwistCommandHandle : public CommandHandle_<TwistCommandHandle, Twist>
385 {
386 public:
387 
388  using Base::operator=;
389 
391  TwistCommandHandle(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : Base(interface, name, field) {}
392  TwistCommandHandle(Twist* command) { *this = command; }
393  virtual ~TwistCommandHandle() {}
394 };
396 
397 class AccelCommandHandle : public CommandHandle_<AccelCommandHandle, Accel>
398 {
399 public:
400 
401  using Base::operator=;
402 
404  AccelCommandHandle(QuadrotorInterface *interface, const std::string& name, const std::string& field = std::string()) : Base(interface, name, field) {}
405  AccelCommandHandle(Accel* command) { *this = command; }
406  virtual ~AccelCommandHandle() {}
407 };
409 
410 class HorizontalVelocityCommandHandle : public CommandHandle_<HorizontalVelocityCommandHandle, Vector3, TwistCommandHandle>
411 {
412 public:
413  using Base::operator=;
414 
417  HorizontalVelocityCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "linear.xy") {}
418  HorizontalVelocityCommandHandle(Vector3* command) { *this = command; }
420 
421  using Base::getCommand;
422  bool getCommand(double &x, double &y) const {
423  x = get()->x;
424  y = get()->y;
425  return true;
426  }
427 
428  using Base::setCommand;
429  void setCommand(double x, double y)
430  {
431  get()->x = x;
432  get()->y = y;
433  }
434 
435  using Base::update;
436  bool update(Twist& command) const {
437  if (!connected()) return false;
438  getCommand(command.linear.x, command.linear.y);
439  return true;
440  }
441 };
443 
444 namespace internal {
446  static Vector3 *get(Twist *twist) { return &(twist->linear); }
447  };
448 }
449 
450 class VerticalVelocityCommandHandle : public CommandHandle_<VerticalVelocityCommandHandle, double, TwistCommandHandle>
451 {
452 public:
453  using Base::operator=;
454 
456  VerticalVelocityCommandHandle(const TwistCommandHandle& other) : Base(other) {}
457  VerticalVelocityCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "linear.z") {}
458  VerticalVelocityCommandHandle(double* command) { *this = command; }
460 
461  using Base::update;
462  bool update(Twist& command) const {
463  if (!connected()) return false;
464  command.linear.z = *get();
465  return true;
466  }
467 };
469 
470 namespace internal {
472  static double *get(Twist *twist) { return &(twist->linear.z); }
473  };
474 }
475 
476 class AngularVelocityCommandHandle : public CommandHandle_<AngularVelocityCommandHandle, double, TwistCommandHandle>
477 {
478 public:
479  using Base::operator=;
480 
482  AngularVelocityCommandHandle(const TwistCommandHandle& other) : Base(other) {}
483  AngularVelocityCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name, "angular.z") {}
484  AngularVelocityCommandHandle(double* command) { *this = command; }
486 
487  using Base::update;
488  bool update(Twist& command) const {
489  if (!connected()) return false;
490  command.linear.z = *get();
491  return true;
492  }
493 };
495 
496 namespace internal {
498  static double *get(Twist *twist) { return &(twist->angular.z); }
499  };
500 }
501 
502 class WrenchCommandHandle : public CommandHandle_<WrenchCommandHandle, Wrench>
503 {
504 public:
505  using Base::operator=;
506 
508  WrenchCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {}
509  virtual ~WrenchCommandHandle() {}
510 };
512 
513 class MotorCommandHandle : public CommandHandle_<MotorCommandHandle, MotorCommand>
514 {
515 public:
516  using Base::operator=;
517 
519  MotorCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {}
520  virtual ~MotorCommandHandle() {}
521 };
523 
524 class AttitudeCommandHandle : public CommandHandle_<AttitudeCommandHandle, AttitudeCommand>
525 {
526 public:
527  using Base::operator=;
528 
530  AttitudeCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {}
532 };
534 
535 class YawrateCommandHandle : public CommandHandle_<YawrateCommandHandle, YawrateCommand>
536 {
537 public:
538  using Base::operator=;
539 
541  YawrateCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {}
543 };
545 
546 class ThrustCommandHandle : public CommandHandle_<ThrustCommandHandle, ThrustCommand>
547 {
548 public:
549  using Base::operator=;
550 
552  ThrustCommandHandle(QuadrotorInterface *interface, const std::string& name) : Base(interface, name) {}
553  virtual ~ThrustCommandHandle() {}
554 };
556 
557 } // namespace hector_quadrotor_interface
558 
559 #endif // HECTOR_QUADROTOR_INTERFACE_HANDLES_H
boost::shared_ptr< TwistHandle > TwistHandlePtr
Definition: handles.h:121
const ValueType & getCommand() const
Definition: handles.h:254
VerticalVelocityCommandHandle(const TwistCommandHandle &other)
Definition: handles.h:456
boost::shared_ptr< YawrateCommandHandle > YawrateCommandHandlePtr
Definition: handles.h:544
boost::shared_ptr< AngularVelocityCommandHandle > AngularVelocityCommandHandlePtr
Definition: handles.h:494
boost::shared_ptr< HeightCommandHandle > HeightCommandHandlePtr
Definition: handles.h:343
boost::shared_ptr< ImuHandle > ImuHandlePtr
Definition: handles.h:159
virtual bool connected() const
Definition: handles.h:76
const ValueType & acceleration() const
Definition: handles.h:133
WrenchCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:508
CommandHandle_(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
Definition: handles.h:242
virtual bool connected() const
Definition: handles.h:144
AccelCommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
Definition: handles.h:404
boost::shared_ptr< StateHandle > StateHandlePtr
Definition: handles.h:146
Derived & operator=(ValueType *source)
Definition: handles.h:249
boost::shared_ptr< AccelerationHandle > AccelerationHandlePtr
Definition: handles.h:135
boost::shared_ptr< PoseCommandHandle > PoseCommandHandlePtr
Definition: handles.h:278
virtual const std::string & getName() const
Definition: handles.h:73
ThrustCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:552
AngularVelocityCommandHandle(const TwistCommandHandle &other)
Definition: handles.h:482
AttitudeCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:530
TwistHandle(QuadrotorInterface *interface)
Definition: handles.h:115
QuadrotorInterface * interface_
Definition: handles.h:84
boost::shared_ptr< void > my_
Definition: handles.h:217
TwistCommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
Definition: handles.h:391
YawrateCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:541
Handle_(QuadrotorInterface *interface, const ValueType *source, const std::string &name, const std::string &field=std::string())
Definition: handles.h:70
boost::shared_ptr< TwistCommandHandle > TwistCommandHandlePtr
Definition: handles.h:395
bool update(ValueType &command) const
Definition: handles.h:258
HorizontalVelocityCommandHandle(const TwistCommandHandle &other)
Definition: handles.h:416
boost::shared_ptr< AccelCommandHandle > AccelCommandHandlePtr
Definition: handles.h:408
Handle_(const std::string &name, const std::string &field=std::string())
Definition: handles.h:68
VerticalVelocityCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:457
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool getCommand(ValueType &command) const
Definition: handles.h:256
boost::shared_ptr< HeadingCommandHandle > HeadingCommandHandlePtr
Definition: handles.h:376
AngularVelocityCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:483
virtual const std::string & getField() const
Definition: handles.h:182
virtual const std::string & getName() const
Definition: handles.h:181
const ValueType & twist() const
Definition: handles.h:119
MotorCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:519
void setCommand(const ValueType &command)
Definition: handles.h:255
ROSLIB_DECL std::string command(const std::string &cmd)
HorizontalVelocityCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:417
CommandHandle_< Derived, T, Parent > Base
Definition: handles.h:238
HeadingCommandHandle(const PoseCommandHandle &other)
Definition: handles.h:357
boost::shared_ptr< HorizontalPositionCommandHandle > HorizontalPositionCommandHandlePtr
Definition: handles.h:315
boost::shared_ptr< ThrustCommandHandle > ThrustCommandHandlePtr
Definition: handles.h:555
const ValueType & pose() const
Definition: handles.h:100
boost::shared_ptr< MotorCommandHandle > MotorCommandHandlePtr
Definition: handles.h:522
boost::shared_ptr< VerticalVelocityCommandHandle > VerticalVelocityCommandHandlePtr
Definition: handles.h:468
double getYaw(const tf2::Quaternion &q)
ImuHandle(QuadrotorInterface *interface, const Imu *imu)
Definition: handles.h:154
PoseHandle(QuadrotorInterface *interface, const Pose *pose)
Definition: handles.h:97
AccelerationHandle(QuadrotorInterface *interface)
Definition: handles.h:129
CommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field)
Definition: handles.h:178
HorizontalPositionCommandHandle(const PoseCommandHandle &other)
Definition: handles.h:286
HeadingCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:358
const ValueType & imu() const
Definition: handles.h:157
PoseHandle(QuadrotorInterface *interface)
Definition: handles.h:96
Handle_(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
Definition: handles.h:69
HeightCommandHandle(const PoseCommandHandle &other)
Definition: handles.h:329
MotorStatusHandle(QuadrotorInterface *interface, const MotorStatus *motor_status)
Definition: handles.h:167
const ValueType & operator*() const
Definition: handles.h:81
Derived & operator=(const ValueType *source)
Definition: handles.h:79
bool connectTo(Derived &input) const
Definition: handles.h:206
bool connectFrom(const Derived &output)
Definition: handles.h:199
HorizontalPositionCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:287
virtual const std::string & getField() const
Definition: handles.h:74
HeightCommandHandle(QuadrotorInterface *interface, const std::string &name)
Definition: handles.h:330
boost::shared_ptr< HorizontalVelocityCommandHandle > HorizontalVelocityCommandHandlePtr
Definition: handles.h:442
TwistHandle(QuadrotorInterface *interface, const Twist *twist)
Definition: handles.h:116
bool getCommand(double &x, double &y) const
Definition: handles.h:422
AccelerationHandle(QuadrotorInterface *interface, const Accel *acceleration)
Definition: handles.h:130
boost::shared_ptr< MotorStatusHandle > MotorStatusHandlePtr
Definition: handles.h:172
const ValueType & motorStatus() const
Definition: handles.h:170
static Derived::ValueType * get(void *)
Definition: handles.h:229
Handle_< Derived, T > Base
Definition: handles.h:66
boost::shared_ptr< PoseHandle > PoseHandlePtr
Definition: handles.h:107
StateHandle(QuadrotorInterface *interface, const Pose *pose, const Twist *twist)
Definition: handles.h:141
boost::shared_ptr< AttitudeCommandHandle > AttitudeCommandHandlePtr
Definition: handles.h:533
boost::shared_ptr< CommandHandle > CommandHandlePtr
Definition: handles.h:225
PoseCommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
Definition: handles.h:274
boost::shared_ptr< WrenchCommandHandle > WrenchCommandHandlePtr
Definition: handles.h:511
#define ROS_DEBUG(...)
virtual bool getCommand(double &x, double &y) const
Definition: handles.h:292


hector_quadrotor_interface
Author(s): Johannes Meyer , Paul Bovbel
autogenerated on Mon Jun 10 2019 13:36:46