lee_position_controller_node.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13 
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  */
20 
21 #ifndef ROTORS_CONTROL_LEE_POSITION_CONTROLLER_NODE_H
22 #define ROTORS_CONTROL_LEE_POSITION_CONTROLLER_NODE_H
23 
24 #include <boost/bind.hpp>
25 #include <Eigen/Eigen>
26 #include <stdio.h>
27 
28 #include <geometry_msgs/PoseStamped.h>
29 #include <mav_msgs/Actuators.h>
30 #include <mav_msgs/AttitudeThrust.h>
32 #include <nav_msgs/Odometry.h>
33 #include <ros/callback_queue.h>
34 #include <ros/ros.h>
35 #include <trajectory_msgs/MultiDOFJointTrajectory.h>
36 
37 #include "rotors_control/common.h"
39 
40 namespace rotors_control {
41 
43  public:
44  LeePositionControllerNode(const ros::NodeHandle& nh, const ros::NodeHandle& private_nh);
46 
47  void InitializeParams();
48  void Publish();
49 
50  private:
53 
55 
56  std::string namespace_;
57 
58  // subscribers
63 
65 
66  mav_msgs::EigenTrajectoryPointDeque commands_;
67  std::deque<ros::Duration> command_waiting_times_;
69 
71 
73  const trajectory_msgs::MultiDOFJointTrajectoryConstPtr& trajectory_reference_msg);
74 
76  const geometry_msgs::PoseStampedConstPtr& pose_msg);
77 
78  void OdometryCallback(const nav_msgs::OdometryConstPtr& odometry_msg);
79 };
80 }
81 
82 #endif // ROTORS_CONTROL_LEE_POSITION_CONTROLLER_NODE_H
void CommandPoseCallback(const geometry_msgs::PoseStampedConstPtr &pose_msg)
void MultiDofJointTrajectoryCallback(const trajectory_msgs::MultiDOFJointTrajectoryConstPtr &trajectory_reference_msg)
void OdometryCallback(const nav_msgs::OdometryConstPtr &odometry_msg)
mav_msgs::EigenTrajectoryPointDeque commands_
LeePositionControllerNode(const ros::NodeHandle &nh, const ros::NodeHandle &private_nh)


rotors_control
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:38:55