#include <mavros_msgs/CommandTOL.h>#include <mavros_msgs/State.h>#include <nav_msgs/Odometry.h>#include <geometry_msgs/Pose.h>#include <geometry_msgs/PoseStamped.h>#include <cmath>#include <math.h>#include <ros/ros.h>#include <std_msgs/Float64.h>#include <std_msgs/String.h>#include <mavros_msgs/CommandBool.h>#include <mavros_msgs/SetMode.h>#include <mavros_msgs/PositionTarget.h>#include <unistd.h>#include <vector>#include <ros/duration.h>#include <iostream>Go to the source code of this file.
Classes | |
| struct | control_api_waypoint |
Functions | |
| void | state_cb (const mavros_msgs::State::ConstPtr &msg) |
| void | enu_2_local (nav_msgs::Odometry current_pose_enu) |
| void | pose_cb (const nav_msgs::Odometry::ConstPtr &msg) |
| void | set_heading (float heading) |
| void | set_destination (float x, float y, float z, float psi) |
| int | wait4connect () |
| int | wait4start () |
| int | initialize_local_frame () |
| int | takeoff (float takeoff_alt) |
| int | check_waypoint_reached () |
| int | land () |
| int | init_publisher_subscriber (ros::NodeHandle controlnode) |
Variables | |
| mavros_msgs::State | current_state_g |
| nav_msgs::Odometry | current_pose_g |
| geometry_msgs::Pose | correction_vector_g |
| geometry_msgs::PoseStamped | waypoint_g |
| float | current_heading_g |
| float | local_offset_g |
| float | correction_heading_g = 0 |
| ros::Publisher | local_pos_pub |
| ros::Subscriber | currentPos |
| ros::Subscriber | state_sub |
| ros::ServiceClient | arming_client |
| ros::ServiceClient | land_client |
| ros::ServiceClient | set_mode_client |
| ros::ServiceClient | takeoff_client |
| void enu_2_local | ( | nav_msgs::Odometry | current_pose_enu | ) |
Definition at line 61 of file control_functions.hpp.
| void pose_cb | ( | const nav_msgs::Odometry::ConstPtr & | msg | ) |
Definition at line 73 of file control_functions.hpp.
| void state_cb | ( | const mavros_msgs::State::ConstPtr & | msg | ) |
Definition at line 57 of file control_functions.hpp.
| ros::ServiceClient arming_client |
Definition at line 40 of file control_functions.hpp.
| float correction_heading_g = 0 |
Definition at line 33 of file control_functions.hpp.
| geometry_msgs::Pose correction_vector_g |
Definition at line 28 of file control_functions.hpp.
| float current_heading_g |
Definition at line 31 of file control_functions.hpp.
| nav_msgs::Odometry current_pose_g |
Definition at line 27 of file control_functions.hpp.
| mavros_msgs::State current_state_g |
Definition at line 26 of file control_functions.hpp.
| ros::Subscriber currentPos |
Definition at line 38 of file control_functions.hpp.
| ros::ServiceClient land_client |
Definition at line 41 of file control_functions.hpp.
| float local_offset_g |
Definition at line 32 of file control_functions.hpp.
| ros::Publisher local_pos_pub |
Definition at line 37 of file control_functions.hpp.
| ros::ServiceClient set_mode_client |
Definition at line 42 of file control_functions.hpp.
| ros::Subscriber state_sub |
Definition at line 39 of file control_functions.hpp.
| ros::ServiceClient takeoff_client |
Definition at line 43 of file control_functions.hpp.
| geometry_msgs::PoseStamped waypoint_g |
Definition at line 29 of file control_functions.hpp.