Public Member Functions | Private Member Functions | Private Attributes | List of all members
rotors_control::LeePositionControllerNode Class Reference

#include <lee_position_controller_node.h>

Public Member Functions

void InitializeParams ()
 
 LeePositionControllerNode (const ros::NodeHandle &nh, const ros::NodeHandle &private_nh)
 
void Publish ()
 
 ~LeePositionControllerNode ()
 

Private Member Functions

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)
 
void TimedCommandCallback (const ros::TimerEvent &e)
 

Private Attributes

ros::Subscriber cmd_multi_dof_joint_trajectory_sub_
 
ros::Subscriber cmd_pose_sub_
 
ros::Subscriber cmd_trajectory_sub_
 
ros::Timer command_timer_
 
std::deque< ros::Durationcommand_waiting_times_
 
mav_msgs::EigenTrajectoryPointDeque commands_
 
LeePositionController lee_position_controller_
 
ros::Publisher motor_velocity_reference_pub_
 
std::string namespace_
 
ros::NodeHandle nh_
 
ros::Subscriber odometry_sub_
 
ros::NodeHandle private_nh_
 

Detailed Description

Definition at line 42 of file lee_position_controller_node.h.

Constructor & Destructor Documentation

◆ LeePositionControllerNode()

rotors_control::LeePositionControllerNode::LeePositionControllerNode ( const ros::NodeHandle nh,
const ros::NodeHandle private_nh 
)

Definition at line 30 of file lee_position_controller_node.cpp.

◆ ~LeePositionControllerNode()

rotors_control::LeePositionControllerNode::~LeePositionControllerNode ( )

Definition at line 54 of file lee_position_controller_node.cpp.

Member Function Documentation

◆ CommandPoseCallback()

void rotors_control::LeePositionControllerNode::CommandPoseCallback ( const geometry_msgs::PoseStampedConstPtr &  pose_msg)
private

Definition at line 101 of file lee_position_controller_node.cpp.

◆ InitializeParams()

void rotors_control::LeePositionControllerNode::InitializeParams ( )

Definition at line 56 of file lee_position_controller_node.cpp.

◆ MultiDofJointTrajectoryCallback()

void rotors_control::LeePositionControllerNode::MultiDofJointTrajectoryCallback ( const trajectory_msgs::MultiDOFJointTrajectoryConstPtr &  trajectory_reference_msg)
private

Definition at line 116 of file lee_position_controller_node.cpp.

◆ OdometryCallback()

void rotors_control::LeePositionControllerNode::OdometryCallback ( const nav_msgs::OdometryConstPtr &  odometry_msg)
private

Definition at line 173 of file lee_position_controller_node.cpp.

◆ Publish()

void rotors_control::LeePositionControllerNode::Publish ( )

Definition at line 98 of file lee_position_controller_node.cpp.

◆ TimedCommandCallback()

void rotors_control::LeePositionControllerNode::TimedCommandCallback ( const ros::TimerEvent e)
private

Definition at line 155 of file lee_position_controller_node.cpp.

Member Data Documentation

◆ cmd_multi_dof_joint_trajectory_sub_

ros::Subscriber rotors_control::LeePositionControllerNode::cmd_multi_dof_joint_trajectory_sub_
private

Definition at line 60 of file lee_position_controller_node.h.

◆ cmd_pose_sub_

ros::Subscriber rotors_control::LeePositionControllerNode::cmd_pose_sub_
private

Definition at line 61 of file lee_position_controller_node.h.

◆ cmd_trajectory_sub_

ros::Subscriber rotors_control::LeePositionControllerNode::cmd_trajectory_sub_
private

Definition at line 59 of file lee_position_controller_node.h.

◆ command_timer_

ros::Timer rotors_control::LeePositionControllerNode::command_timer_
private

Definition at line 68 of file lee_position_controller_node.h.

◆ command_waiting_times_

std::deque<ros::Duration> rotors_control::LeePositionControllerNode::command_waiting_times_
private

Definition at line 67 of file lee_position_controller_node.h.

◆ commands_

mav_msgs::EigenTrajectoryPointDeque rotors_control::LeePositionControllerNode::commands_
private

Definition at line 66 of file lee_position_controller_node.h.

◆ lee_position_controller_

LeePositionController rotors_control::LeePositionControllerNode::lee_position_controller_
private

Definition at line 54 of file lee_position_controller_node.h.

◆ motor_velocity_reference_pub_

ros::Publisher rotors_control::LeePositionControllerNode::motor_velocity_reference_pub_
private

Definition at line 64 of file lee_position_controller_node.h.

◆ namespace_

std::string rotors_control::LeePositionControllerNode::namespace_
private

Definition at line 56 of file lee_position_controller_node.h.

◆ nh_

ros::NodeHandle rotors_control::LeePositionControllerNode::nh_
private

Definition at line 51 of file lee_position_controller_node.h.

◆ odometry_sub_

ros::Subscriber rotors_control::LeePositionControllerNode::odometry_sub_
private

Definition at line 62 of file lee_position_controller_node.h.

◆ private_nh_

ros::NodeHandle rotors_control::LeePositionControllerNode::private_nh_
private

Definition at line 52 of file lee_position_controller_node.h.


The documentation for this class was generated from the following files:


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