#include <joy.h>
| Public Member Functions | |
| Joy () | |
| Private Types | |
| typedef sensor_msgs::Joy::_buttons_type | ButtonType | 
| Private Member Functions | |
| void | APCommandCallback (const rosflight_msgs::CommandConstPtr &msg) | 
| void | JoyCallback (const sensor_msgs::JoyConstPtr &msg) | 
| void | PauseSimulation () | 
| void | Publish () | 
| void | ResetMav () | 
| void | ResumeSimulation () | 
| void | StopMav () | 
| Private Attributes | |
| rosflight_msgs::Command | autopilot_command_ | 
| ros::Subscriber | autopilot_command_sub_ | 
| std::string | autopilot_command_topic_ | 
| Axes | axes_ | 
| Buttons | buttons_ | 
| rosflight_msgs::Command | command_msg_ | 
| ros::Publisher | command_pub_ | 
| std::string | command_topic_ | 
| double | current_altitude_setpoint_ | 
| sensor_msgs::Joy | current_joy_ | 
| double | current_x_setpoint_ | 
| double | current_y_setpoint_ | 
| double | current_yaw_setpoint_ | 
| double | current_yaw_vel_ | 
| double | equilibrium_thrust_ | 
| std::string | gazebo_ns_ | 
| ros::Subscriber | joy_sub_ | 
| double | last_time_ | 
| double | mass_ | 
| std::string | mav_name_ | 
| Max | max_ | 
| std::string | namespace_ | 
| ros::NodeHandle | nh_ | 
| bool | override_autopilot_ = true | 
| bool | paused = true | 
| geometry_msgs::Pose | reset_pose_ | 
| geometry_msgs::Twist | reset_twist_ | 
| double | v_yaw_step_ | 
| 
 | private | 
| 
 | private | 
| 
 | private | 
| 
 | private | 
| 
 | private | 
| 
 | private | 
| 
 | private | 
| 
 | private |