29 #ifndef HECTOR_QUADROTOR_INTERFACE_HANDLES_H 30 #define HECTOR_QUADROTOR_INTERFACE_HANDLES_H 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> 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;
61 template <
class Derived,
typename T>
79 Derived&
operator=(
const ValueType *source) {
value_ = source;
return static_cast<Derived &
>(*this); }
80 const ValueType *
get()
const {
return value_; }
93 using Base::operator=;
100 const ValueType&
pose()
const {
return *
get(); }
102 void getEulerRPY(
double &roll,
double &pitch,
double &yaw)
const;
104 Vector3 toBody(
const Vector3& nav)
const;
105 Vector3 fromBody(
const Vector3& nav)
const;
112 using Base::operator=;
119 const ValueType&
twist()
const {
return *
get(); }
126 using Base::operator=;
151 using Base::operator=;
157 const ValueType&
imu()
const {
return *
get(); }
164 using Base::operator=;
186 void *
get()
const {
return 0; }
197 template <
typename T> T*
ownData(T* data) { my_.reset(data);
return data; }
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);
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);
223 bool wasNew()
const {
bool old = new_value_; new_value_ =
false;
return old; }
229 static typename Derived::ValueType *
get(
void *) {
return 0; }
233 template <
class Derived,
typename T,
class Parent = CommandHandle>
246 virtual void reset() { command_ = 0; Parent::reset(); }
248 using Parent::operator=;
249 Derived&
operator=(ValueType *source) { command_ = source;
return static_cast<Derived &
>(*this); }
254 const ValueType&
getCommand()
const { this->new_value_ =
false;
return *
get(); }
255 void setCommand(
const ValueType& command) { this->new_value_ =
true; *
get() = command; }
260 command = getCommand();
271 using Base::operator=;
283 using Base::operator=;
291 using Base::getCommand;
298 using Base::setCommand;
301 this->new_value_ =
true;
309 getCommand(command.position.x, command.position.y);
313 void getError(
const PoseHandle &pose,
double &x,
double &y)
const;
319 static Point *
get(Pose *pose) {
return &(pose->position); }
326 using Base::operator=;
337 command.position.z = getCommand();
341 double getError(
const PoseHandle &pose)
const;
347 static double *
get(Pose *pose) {
return &(pose->position.z); }
354 using Base::operator=;
362 using Base::getCommand;
363 double getCommand()
const;
365 using Base::setCommand;
366 void setCommand(
double command);
369 bool update(Pose& command)
const;
371 double getError(
const PoseHandle &pose)
const;
380 static Quaternion *
get(Pose *pose) {
return &(pose->orientation); }
388 using Base::operator=;
401 using Base::operator=;
413 using Base::operator=;
421 using Base::getCommand;
428 using Base::setCommand;
438 getCommand(command.linear.x, command.linear.y);
446 static Vector3 *
get(Twist *twist) {
return &(twist->linear); }
453 using Base::operator=;
464 command.linear.z = *
get();
472 static double *
get(Twist *twist) {
return &(twist->linear.z); }
479 using Base::operator=;
490 command.linear.z = *
get();
498 static double *
get(Twist *twist) {
return &(twist->angular.z); }
505 using Base::operator=;
516 using Base::operator=;
527 using Base::operator=;
538 using Base::operator=;
549 using Base::operator=;
559 #endif // HECTOR_QUADROTOR_INTERFACE_HANDLES_H virtual ~HeightCommandHandle()
boost::shared_ptr< TwistHandle > TwistHandlePtr
virtual ~HorizontalPositionCommandHandle()
virtual ~MotorStatusHandle()
const ValueType & getCommand() const
VerticalVelocityCommandHandle(const TwistCommandHandle &other)
VerticalVelocityCommandHandle(double *command)
boost::shared_ptr< YawrateCommandHandle > YawrateCommandHandlePtr
bool update(Twist &command) const
boost::shared_ptr< AngularVelocityCommandHandle > AngularVelocityCommandHandlePtr
boost::shared_ptr< HeightCommandHandle > HeightCommandHandlePtr
boost::shared_ptr< ImuHandle > ImuHandlePtr
virtual bool connected() const
bool update(Pose &command) const
virtual ~AttitudeCommandHandle()
virtual bool connected() const
const ValueType & acceleration() const
WrenchCommandHandle(QuadrotorInterface *interface, const std::string &name)
CommandHandle_(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
HorizontalVelocityCommandHandle(Vector3 *command)
virtual bool connected() const
AccelCommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
boost::shared_ptr< StateHandle > StateHandlePtr
virtual ~WrenchCommandHandle()
Derived & operator=(ValueType *source)
boost::shared_ptr< AccelerationHandle > AccelerationHandlePtr
boost::shared_ptr< PoseCommandHandle > PoseCommandHandlePtr
virtual ~CommandHandle_()
virtual const std::string & getName() const
bool update(Twist &command) const
ThrustCommandHandle(QuadrotorInterface *interface, const std::string &name)
AngularVelocityCommandHandle(const TwistCommandHandle &other)
HorizontalPositionCommandHandle()
virtual ~TwistCommandHandle()
AttitudeCommandHandle(QuadrotorInterface *interface, const std::string &name)
TwistHandle(QuadrotorInterface *interface)
QuadrotorInterface * interface_
boost::shared_ptr< void > my_
TwistCommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
YawrateCommandHandle(QuadrotorInterface *interface, const std::string &name)
Handle_(QuadrotorInterface *interface, const ValueType *source, const std::string &name, const std::string &field=std::string())
boost::shared_ptr< TwistCommandHandle > TwistCommandHandlePtr
bool update(ValueType &command) const
HorizontalVelocityCommandHandle(const TwistCommandHandle &other)
boost::shared_ptr< AccelCommandHandle > AccelCommandHandlePtr
Handle_(const std::string &name, const std::string &field=std::string())
VerticalVelocityCommandHandle(QuadrotorInterface *interface, const std::string &name)
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
bool getCommand(ValueType &command) const
boost::shared_ptr< HeadingCommandHandle > HeadingCommandHandlePtr
AngularVelocityCommandHandle(QuadrotorInterface *interface, const std::string &name)
virtual const std::string & getField() const
CommandHandle_(const Parent &other)
virtual const std::string & getName() const
PoseCommandHandle(Pose *command)
const ValueType & twist() const
MotorCommandHandle(QuadrotorInterface *interface, const std::string &name)
void setCommand(const ValueType &command)
ROSLIB_DECL std::string command(const std::string &cmd)
HorizontalVelocityCommandHandle(QuadrotorInterface *interface, const std::string &name)
CommandHandle_< Derived, T, Parent > Base
HeadingCommandHandle(const PoseCommandHandle &other)
boost::shared_ptr< HorizontalPositionCommandHandle > HorizontalPositionCommandHandlePtr
boost::shared_ptr< ThrustCommandHandle > ThrustCommandHandlePtr
void setCommand(double x, double y)
TwistCommandHandle(Twist *command)
AngularVelocityCommandHandle()
const ValueType & pose() const
boost::shared_ptr< MotorCommandHandle > MotorCommandHandlePtr
boost::shared_ptr< VerticalVelocityCommandHandle > VerticalVelocityCommandHandlePtr
double getYaw(const tf2::Quaternion &q)
HeadingCommandHandle(Quaternion *command)
ImuHandle(QuadrotorInterface *interface, const Imu *imu)
PoseHandle(QuadrotorInterface *interface, const Pose *pose)
AccelerationHandle(QuadrotorInterface *interface)
CommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field)
HorizontalPositionCommandHandle(const PoseCommandHandle &other)
virtual ~AngularVelocityCommandHandle()
HeadingCommandHandle(QuadrotorInterface *interface, const std::string &name)
const ValueType & imu() const
virtual ~VerticalVelocityCommandHandle()
PoseHandle(QuadrotorInterface *interface)
Handle_(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
HeightCommandHandle(const PoseCommandHandle &other)
MotorStatusHandle(QuadrotorInterface *interface, const MotorStatus *motor_status)
virtual ~HeadingCommandHandle()
const ValueType & operator*() const
AngularVelocityCommandHandle(double *command)
HorizontalVelocityCommandHandle()
HeightCommandHandle(double *command)
ValueType & operator*() const
Derived & operator=(const ValueType *source)
bool connectTo(Derived &input) const
bool connectFrom(const Derived &output)
HorizontalPositionCommandHandle(QuadrotorInterface *interface, const std::string &name)
virtual const std::string & getField() const
HeightCommandHandle(QuadrotorInterface *interface, const std::string &name)
bool update(Twist &command) const
HorizontalPositionCommandHandle(Point *command)
bool update(Pose &command) const
virtual void setCommand(double x, double y)
virtual ~MotorCommandHandle()
AccelCommandHandle(Accel *command)
boost::shared_ptr< HorizontalVelocityCommandHandle > HorizontalVelocityCommandHandlePtr
TwistHandle(QuadrotorInterface *interface, const Twist *twist)
bool getCommand(double &x, double &y) const
AccelerationHandle(QuadrotorInterface *interface, const Accel *acceleration)
boost::shared_ptr< MotorStatusHandle > MotorStatusHandlePtr
virtual ~AccelerationHandle()
const ValueType & motorStatus() const
static Derived::ValueType * get(void *)
QuadrotorInterface * interface_
Handle_< Derived, T > Base
virtual ~ThrustCommandHandle()
virtual ~HorizontalVelocityCommandHandle()
boost::shared_ptr< PoseHandle > PoseHandlePtr
virtual ~PoseCommandHandle()
StateHandle(QuadrotorInterface *interface, const Pose *pose, const Twist *twist)
virtual ~AccelCommandHandle()
VerticalVelocityCommandHandle()
boost::shared_ptr< AttitudeCommandHandle > AttitudeCommandHandlePtr
boost::shared_ptr< CommandHandle > CommandHandlePtr
virtual ~YawrateCommandHandle()
PoseCommandHandle(QuadrotorInterface *interface, const std::string &name, const std::string &field=std::string())
boost::shared_ptr< WrenchCommandHandle > WrenchCommandHandlePtr
virtual bool getCommand(double &x, double &y) const