29 #ifndef HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H 30 #define HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H 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> 45 #include <boost/thread/mutex.hpp> 46 #include <boost/thread/condition.hpp> 64 void setTwist(
const geometry_msgs::Twist& twist);
72 void addPWMToQueue(
const hector_uav_msgs::MotorPWMConstPtr& pwm);
75 void f(
const double xin[4],
const double uin[10],
double dt,
double y[14],
double xpred[4])
const;
99 #endif // HECTOR_QUADROTOR_MODEL_QUADROTOR_PROPULSION_H bool configure(const ros::NodeHandle ¶m=ros::NodeHandle("~"))
const hector_uav_msgs::MotorStatus & getMotorStatus() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
bool processQueue(const ros::Time ×tamp, const ros::Duration &tolerance=ros::Duration(), const ros::Duration &delay=ros::Duration(), const ros::WallDuration &wait=ros::WallDuration(), ros::CallbackQueue *callback_queue=0)
PropulsionModel * propulsion_model_
const geometry_msgs::Wrench & getWrench() const
const hector_uav_msgs::Supply & getSupply() const
std::queue< hector_uav_msgs::MotorPWMConstPtr > command_queue_
geometry_msgs::Wrench wrench_
boost::mutex command_queue_mutex_
ros::Time last_command_time_
ROSLIB_DECL std::string command(const std::string &cmd)
void addPWMToQueue(const hector_uav_msgs::MotorPWMConstPtr &pwm)
boost::condition command_condition_
hector_uav_msgs::MotorStatus motor_status_
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)
hector_uav_msgs::Supply supply_
void setInitialSupplyVoltage(double voltage)
void setTwist(const geometry_msgs::Twist &twist)
void addCommandToQueue(const hector_uav_msgs::MotorCommandConstPtr &command)