21 #ifndef ROTORS_CONTROL_LEE_POSITION_CONTROLLER_NODE_H 22 #define ROTORS_CONTROL_LEE_POSITION_CONTROLLER_NODE_H 24 #include <boost/bind.hpp> 25 #include <Eigen/Eigen> 28 #include <geometry_msgs/PoseStamped.h> 29 #include <mav_msgs/Actuators.h> 30 #include <mav_msgs/AttitudeThrust.h> 32 #include <nav_msgs/Odometry.h> 35 #include <trajectory_msgs/MultiDOFJointTrajectory.h> 73 const trajectory_msgs::MultiDOFJointTrajectoryConstPtr& trajectory_reference_msg);
76 const geometry_msgs::PoseStampedConstPtr& pose_msg);
82 #endif // ROTORS_CONTROL_LEE_POSITION_CONTROLLER_NODE_H ros::Subscriber cmd_trajectory_sub_
ros::NodeHandle private_nh_
ros::Timer command_timer_
void CommandPoseCallback(const geometry_msgs::PoseStampedConstPtr &pose_msg)
void MultiDofJointTrajectoryCallback(const trajectory_msgs::MultiDOFJointTrajectoryConstPtr &trajectory_reference_msg)
LeePositionController lee_position_controller_
void OdometryCallback(const nav_msgs::OdometryConstPtr &odometry_msg)
ros::Subscriber cmd_pose_sub_
mav_msgs::EigenTrajectoryPointDeque commands_
void TimedCommandCallback(const ros::TimerEvent &e)
ros::Subscriber cmd_multi_dof_joint_trajectory_sub_
std::deque< ros::Duration > command_waiting_times_
LeePositionControllerNode(const ros::NodeHandle &nh, const ros::NodeHandle &private_nh)
ros::Publisher motor_velocity_reference_pub_
ros::Subscriber odometry_sub_
~LeePositionControllerNode()