#include <ros/ros.h>#include <std_msgs/Float64.h>#include <std_msgs/Bool.h>#include <mav_msgs/Height.h>#include <sensor_msgs/Imu.h>#include <asctec_msgs/common.h>#include <asctec_msgs/IMUCalcData.h>#include <asctec_msgs/CtrlInput.h>#include <asctec_msgs/LLStatus.h>#include <boost/thread/mutex.hpp>#include <tf/transform_datatypes.h>#include <mav_srvs/SetMotorsOnOff.h>#include <mav_srvs/GetMotorsOnOff.h>

Go to the source code of this file.
Classes | |
| class | asctec::AsctecProc |
Namespaces | |
| namespace | asctec |
Variables | |
| const double | asctec::ASC_TO_ROS_ACC = (1.0 / 10000.0) * 9.81 |
| const double | asctec::ASC_TO_ROS_ANGLE = (1.0 / 1000.0) * 3.14159265 / 180.0 |
| const double | asctec::ASC_TO_ROS_ANGVEL = (1.0 / 64.8) * 3.14159265 / 180.0 |
| const double | asctec::ASC_TO_ROS_HEIGHT = (1.0 / 1000.0) |
| const double | asctec::ROS_TO_ASC_PITCH = 2047.0 |
| const double | asctec::ROS_TO_ASC_ROLL = 2047.0 |
| const double | asctec::ROS_TO_ASC_THRUST = 4095.0 |
| const double | asctec::ROS_TO_ASC_YAW_RATE = 2047.0/4.43 |