Definition at line 17 of file controller.cpp.
◆ State
| Enumerator |
|---|
| Idle | |
| Automatic | |
| TakingOff | |
| Landing | |
Definition at line 217 of file controller.cpp.
◆ Controller()
| Controller::Controller |
( |
const std::string & |
worldFrame, |
|
|
const std::string & |
frame, |
|
|
const ros::NodeHandle & |
n |
|
) |
| |
|
inline |
◆ getTransform()
| void Controller::getTransform |
( |
const std::string & |
sourceFrame, |
|
|
const std::string & |
targetFrame, |
|
|
tf::StampedTransform & |
result |
|
) |
| |
|
inlineprivate |
◆ goalChanged()
| void Controller::goalChanged |
( |
const geometry_msgs::PoseStamped::ConstPtr & |
msg | ) |
|
|
inlineprivate |
◆ iteration()
◆ land()
| bool Controller::land |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
inlineprivate |
◆ pidReset()
| void Controller::pidReset |
( |
| ) |
|
|
inlineprivate |
◆ run()
| void Controller::run |
( |
double |
frequency | ) |
|
|
inline |
◆ takeoff()
| bool Controller::takeoff |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
inlineprivate |
◆ m_frame
| std::string Controller::m_frame |
|
private |
◆ m_goal
| geometry_msgs::PoseStamped Controller::m_goal |
|
private |
◆ m_listener
◆ m_pidX
◆ m_pidY
◆ m_pidYaw
◆ m_pidZ
◆ m_pubNav
◆ m_serviceLand
◆ m_serviceTakeoff
◆ m_startZ
| float Controller::m_startZ |
|
private |
◆ m_state
| State Controller::m_state |
|
private |
◆ m_subscribeGoal
◆ m_thrust
| float Controller::m_thrust |
|
private |
◆ m_worldFrame
| std::string Controller::m_worldFrame |
|
private |
The documentation for this class was generated from the following file: