Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
Controller Class Reference

Public Member Functions

 Controller (const std::string &worldFrame, const std::string &frame, const ros::NodeHandle &n)
 
void run (double frequency)
 

Private Types

enum  State { Idle = 0, Automatic = 1, TakingOff = 2, Landing = 3 }
 

Private Member Functions

void getTransform (const std::string &sourceFrame, const std::string &targetFrame, tf::StampedTransform &result)
 
void goalChanged (const geometry_msgs::PoseStamped::ConstPtr &msg)
 
void iteration (const ros::TimerEvent &e)
 
bool land (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
void pidReset ()
 
bool takeoff (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 

Private Attributes

std::string m_frame
 
geometry_msgs::PoseStamped m_goal
 
tf::TransformListener m_listener
 
PID m_pidX
 
PID m_pidY
 
PID m_pidYaw
 
PID m_pidZ
 
ros::Publisher m_pubNav
 
ros::ServiceServer m_serviceLand
 
ros::ServiceServer m_serviceTakeoff
 
float m_startZ
 
State m_state
 
ros::Subscriber m_subscribeGoal
 
float m_thrust
 
std::string m_worldFrame
 

Detailed Description

Definition at line 17 of file controller.cpp.

Member Enumeration Documentation

◆ State

enum Controller::State
private
Enumerator
Idle 
Automatic 
TakingOff 
Landing 

Definition at line 217 of file controller.cpp.

Constructor & Destructor Documentation

◆ Controller()

Controller::Controller ( const std::string &  worldFrame,
const std::string &  frame,
const ros::NodeHandle n 
)
inline

Definition at line 21 of file controller.cpp.

Member Function Documentation

◆ getTransform()

void Controller::getTransform ( const std::string &  sourceFrame,
const std::string &  targetFrame,
tf::StampedTransform result 
)
inlineprivate

Definition at line 119 of file controller.cpp.

◆ goalChanged()

void Controller::goalChanged ( const geometry_msgs::PoseStamped::ConstPtr &  msg)
inlineprivate

Definition at line 89 of file controller.cpp.

◆ iteration()

void Controller::iteration ( const ros::TimerEvent e)
inlineprivate

Definition at line 135 of file controller.cpp.

◆ land()

bool Controller::land ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
inlineprivate

Definition at line 109 of file controller.cpp.

◆ pidReset()

void Controller::pidReset ( )
inlineprivate

Definition at line 127 of file controller.cpp.

◆ run()

void Controller::run ( double  frequency)
inline

Definition at line 81 of file controller.cpp.

◆ takeoff()

bool Controller::takeoff ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
inlineprivate

Definition at line 95 of file controller.cpp.

Member Data Documentation

◆ m_frame

std::string Controller::m_frame
private

Definition at line 227 of file controller.cpp.

◆ m_goal

geometry_msgs::PoseStamped Controller::m_goal
private

Definition at line 235 of file controller.cpp.

◆ m_listener

tf::TransformListener Controller::m_listener
private

Definition at line 229 of file controller.cpp.

◆ m_pidX

PID Controller::m_pidX
private

Definition at line 230 of file controller.cpp.

◆ m_pidY

PID Controller::m_pidY
private

Definition at line 231 of file controller.cpp.

◆ m_pidYaw

PID Controller::m_pidYaw
private

Definition at line 233 of file controller.cpp.

◆ m_pidZ

PID Controller::m_pidZ
private

Definition at line 232 of file controller.cpp.

◆ m_pubNav

ros::Publisher Controller::m_pubNav
private

Definition at line 228 of file controller.cpp.

◆ m_serviceLand

ros::ServiceServer Controller::m_serviceLand
private

Definition at line 238 of file controller.cpp.

◆ m_serviceTakeoff

ros::ServiceServer Controller::m_serviceTakeoff
private

Definition at line 237 of file controller.cpp.

◆ m_startZ

float Controller::m_startZ
private

Definition at line 240 of file controller.cpp.

◆ m_state

State Controller::m_state
private

Definition at line 234 of file controller.cpp.

◆ m_subscribeGoal

ros::Subscriber Controller::m_subscribeGoal
private

Definition at line 236 of file controller.cpp.

◆ m_thrust

float Controller::m_thrust
private

Definition at line 239 of file controller.cpp.

◆ m_worldFrame

std::string Controller::m_worldFrame
private

Definition at line 226 of file controller.cpp.


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


crazyflie_controller
Author(s): Wolfgang Hoenig
autogenerated on Mon Feb 28 2022 22:11:43