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 |
Definition at line 17 of file controller.cpp.
enum Controller::State [private] |
Definition at line 217 of file controller.cpp.
| Controller::Controller | ( | const std::string & | worldFrame, |
| const std::string & | frame, | ||
| const ros::NodeHandle & | n | ||
| ) | [inline] |
Definition at line 21 of file controller.cpp.
| void Controller::getTransform | ( | const std::string & | sourceFrame, |
| const std::string & | targetFrame, | ||
| tf::StampedTransform & | result | ||
| ) | [inline, private] |
Definition at line 119 of file controller.cpp.
| void Controller::goalChanged | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) | [inline, private] |
Definition at line 89 of file controller.cpp.
| void Controller::iteration | ( | const ros::TimerEvent & | e | ) | [inline, private] |
Definition at line 135 of file controller.cpp.
| bool Controller::land | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [inline, private] |
Definition at line 109 of file controller.cpp.
| void Controller::pidReset | ( | ) | [inline, private] |
Definition at line 127 of file controller.cpp.
| void Controller::run | ( | double | frequency | ) | [inline] |
Definition at line 81 of file controller.cpp.
| bool Controller::takeoff | ( | std_srvs::Empty::Request & | req, |
| std_srvs::Empty::Response & | res | ||
| ) | [inline, private] |
Definition at line 95 of file controller.cpp.
std::string Controller::m_frame [private] |
Definition at line 227 of file controller.cpp.
geometry_msgs::PoseStamped Controller::m_goal [private] |
Definition at line 235 of file controller.cpp.
tf::TransformListener Controller::m_listener [private] |
Definition at line 229 of file controller.cpp.
PID Controller::m_pidX [private] |
Definition at line 230 of file controller.cpp.
PID Controller::m_pidY [private] |
Definition at line 231 of file controller.cpp.
PID Controller::m_pidYaw [private] |
Definition at line 233 of file controller.cpp.
PID Controller::m_pidZ [private] |
Definition at line 232 of file controller.cpp.
ros::Publisher Controller::m_pubNav [private] |
Definition at line 228 of file controller.cpp.
ros::ServiceServer Controller::m_serviceLand [private] |
Definition at line 238 of file controller.cpp.
Definition at line 237 of file controller.cpp.
float Controller::m_startZ [private] |
Definition at line 240 of file controller.cpp.
State Controller::m_state [private] |
Definition at line 234 of file controller.cpp.
ros::Subscriber Controller::m_subscribeGoal [private] |
Definition at line 236 of file controller.cpp.
float Controller::m_thrust [private] |
Definition at line 239 of file controller.cpp.
std::string Controller::m_worldFrame [private] |
Definition at line 226 of file controller.cpp.