3 #include <std_srvs/Empty.h> 4 #include <geometry_msgs/Twist.h> 11 const std::string& name) {
13 n.getParam(name, value);
22 const std::string& worldFrame,
23 const std::string& frame,
33 get(n,
"PIDs/X/minOutput"),
34 get(n,
"PIDs/X/maxOutput"),
35 get(n,
"PIDs/X/integratorMin"),
36 get(n,
"PIDs/X/integratorMax"),
42 get(n,
"PIDs/Y/minOutput"),
43 get(n,
"PIDs/Y/maxOutput"),
44 get(n,
"PIDs/Y/integratorMin"),
45 get(n,
"PIDs/Y/integratorMax"),
51 get(n,
"PIDs/Z/minOutput"),
52 get(n,
"PIDs/Z/maxOutput"),
53 get(n,
"PIDs/Z/integratorMin"),
54 get(n,
"PIDs/Z/integratorMax"),
57 get(n,
"PIDs/Yaw/kp"),
58 get(n,
"PIDs/Yaw/kd"),
59 get(n,
"PIDs/Yaw/ki"),
60 get(n,
"PIDs/Yaw/minOutput"),
61 get(n,
"PIDs/Yaw/maxOutput"),
62 get(n,
"PIDs/Yaw/integratorMin"),
63 get(n,
"PIDs/Yaw/integratorMax"),
81 void run(
double frequency)
90 const geometry_msgs::PoseStamped::ConstPtr& msg)
96 std_srvs::Empty::Request& req,
97 std_srvs::Empty::Response& res)
110 std_srvs::Empty::Request& req,
111 std_srvs::Empty::Response& res)
120 const std::string& sourceFrame,
121 const std::string& targetFrame,
155 geometry_msgs::Twist msg;
169 geometry_msgs::Twist msg;
179 geometry_msgs::PoseStamped targetWorld;
180 targetWorld.header.stamp = transform.
stamp_;
182 targetWorld.pose =
m_goal.pose;
184 geometry_msgs::PoseStamped targetDrone;
190 targetDrone.pose.orientation.x,
191 targetDrone.pose.orientation.y,
192 targetDrone.pose.orientation.z,
193 targetDrone.pose.orientation.w
194 )).
getRPY(roll, pitch, yaw);
196 geometry_msgs::Twist msg;
197 msg.linear.x =
m_pidX.
update(0, targetDrone.pose.position.x);
198 msg.linear.y =
m_pidY.
update(0.0, targetDrone.pose.position.y);
199 msg.linear.z =
m_pidZ.
update(0.0, targetDrone.pose.position.z);
208 geometry_msgs::Twist msg;
243 int main(
int argc,
char **argv)
249 std::string worldFrame;
250 n.
param<std::string>(
"worldFrame", worldFrame,
"/world");
254 n.
param(
"frequency", frequency, 50.0);
257 controller.
run(frequency);
void getTransform(const std::string &sourceFrame, const std::string &targetFrame, tf::StampedTransform &result)
void iteration(const ros::TimerEvent &e)
bool takeoff(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void publish(const boost::shared_ptr< M > &message) const
float update(float value, float targetValue)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::ServiceServer m_serviceLand
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool land(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
geometry_msgs::PoseStamped m_goal
ros::ServiceServer m_serviceTakeoff
ROSCPP_DECL void spin(Spinner &spinner)
TFSIMD_FORCE_INLINE const tfScalar & z() const
ros::Subscriber m_subscribeGoal
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
tf::TransformListener m_listener
void goalChanged(const geometry_msgs::PoseStamped::ConstPtr &msg)
bool getParam(const std::string &key, std::string &s) const
void run(double frequency)
Controller(const std::string &worldFrame, const std::string &frame, const ros::NodeHandle &n)
double get(const ros::NodeHandle &n, const std::string &name)
int main(int argc, char **argv)
void setIntegral(float integral)