quadrotor_propulsion.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_MODEL_QUADROTOR_PROPULSION_H
30 #define HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H
31 
32 #include <hector_uav_msgs/Supply.h>
33 #include <hector_uav_msgs/MotorStatus.h>
34 #include <hector_uav_msgs/MotorCommand.h>
35 #include <hector_uav_msgs/MotorPWM.h>
36 #include <geometry_msgs/Twist.h>
37 #include <geometry_msgs/Wrench.h>
38 
39 #include <ros/forwards.h>
40 #include <ros/node_handle.h>
41 #include <ros/time.h>
42 
43 #include <queue>
44 
45 #include <boost/thread/mutex.hpp>
46 #include <boost/thread/condition.hpp>
47 
48 namespace hector_quadrotor_model
49 {
50 
52 {
53 public:
56 
57  bool configure(const ros::NodeHandle &param = ros::NodeHandle("~"));
58  void reset();
59  void update(double dt);
60 
61  void engage();
62  void shutdown();
63 
64  void setTwist(const geometry_msgs::Twist& twist);
65  void setVoltage(const hector_uav_msgs::MotorPWM& command);
66 
67  const geometry_msgs::Wrench& getWrench() const { return wrench_; }
68  const hector_uav_msgs::Supply& getSupply() const { return supply_; }
69  const hector_uav_msgs::MotorStatus& getMotorStatus() const { return motor_status_; }
70 
71  void addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr& command);
72  void addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr& pwm);
73  bool processQueue(const ros::Time& timestamp, const ros::Duration& tolerance = ros::Duration(), const ros::Duration& delay = ros::Duration(), const ros::WallDuration &wait = ros::WallDuration(), ros::CallbackQueue *callback_queue = 0);
74 
75  void f(const double xin[4], const double uin[10], double dt, double y[14], double xpred[4]) const;
76 
77  void setInitialSupplyVoltage(double voltage) { initial_voltage_ = voltage; }
78 
79 private:
80  geometry_msgs::Wrench wrench_;
81  hector_uav_msgs::Supply supply_;
82  hector_uav_msgs::MotorStatus motor_status_;
84 
86 
87  std::queue<hector_uav_msgs::MotorPWMConstPtr> command_queue_;
88  boost::mutex command_queue_mutex_;
89  boost::condition command_condition_;
90 
91  boost::mutex mutex_;
92 
95 };
96 
97 }
98 
99 #endif // HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H
bool configure(const ros::NodeHandle &param=ros::NodeHandle("~"))
const hector_uav_msgs::MotorStatus & getMotorStatus() const
bool param(const std::string &param_name, T &param_val, const T &default_val)
bool processQueue(const ros::Time &timestamp, const ros::Duration &tolerance=ros::Duration(), const ros::Duration &delay=ros::Duration(), const ros::WallDuration &wait=ros::WallDuration(), ros::CallbackQueue *callback_queue=0)
const geometry_msgs::Wrench & getWrench() const
const hector_uav_msgs::Supply & getSupply() const
std::queue< hector_uav_msgs::MotorPWMConstPtr > command_queue_
ROSLIB_DECL std::string command(const std::string &cmd)
void addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr &pwm)
void f(const double xin[4], const double uin[10], double dt, double y[14], double xpred[4]) const
void setVoltage(const hector_uav_msgs::MotorPWM &command)
void setTwist(const geometry_msgs::Twist &twist)
void addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr &command)


hector_quadrotor_model
Author(s): Johannes Meyer , Alexander Sendobry
autogenerated on Mon Jun 10 2019 13:36:56