Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef ASCTECINTERFACE_H_
00033 #define ASCTECINTERFACE_H_
00034
00035 #include <ros/ros.h>
00036 #include <tf/transform_datatypes.h>
00037 #include "comm.h"
00038
00039
00040 #include <asctec_hl_comm/GpsCustom.h>
00041 #include <asctec_hl_comm/mav_ctrl.h>
00042 #include <asctec_hl_comm/mav_rcdata.h>
00043 #include <asctec_hl_comm/mav_status.h>
00044 #include <geometry_msgs/PointStamped.h>
00045 #include <geometry_msgs/Vector3Stamped.h>
00046 #include <sensor_msgs/Imu.h>
00047 #include <sensor_msgs/NavSatFix.h>
00048 #include <sensor_msgs/Joy.h>
00049
00050
00051 #include <mav_msgs/RollPitchYawrateThrust.h>
00052
00053
00054
00055 #include <asctec_hl_comm/MavCtrlSrv.h>
00056 #include <asctec_hl_comm/mav_ctrl_motors.h>
00057
00058
00059 #include <dynamic_reconfigure/server.h>
00060 #include <asctec_hl_interface/HLInterfaceConfig.h>
00061
00062 typedef dynamic_reconfigure::Server<asctec_hl_interface::HLInterfaceConfig> ReconfigureServer;
00063
00064 #include <diagnostic_updater/diagnostic_updater.h>
00065 #include <diagnostic_updater/update_functions.h>
00066
00067
00068
00069
00070
00071
00072 class HLInterface
00073 {
00074 private:
00075
00076 ros::NodeHandle nh_;
00077 ros::NodeHandle pnh_;
00078 CommPtr & comm_;
00079
00080 std::string frame_id_;
00081 std::string mav_type_;
00082
00083 ros::Publisher gps_pub_;
00084 ros::Publisher gps_custom_pub_;
00085 ros::Publisher imu_ros_pub_;
00086 ros::Publisher motors_pub_;
00087 ros::Publisher pressure_height_pub_;
00088 ros::Publisher rc_pub_;
00089 ros::Publisher rc_joy_pub_;
00090 ros::Publisher status_pub_;
00091 ros::Publisher mag_pub_;
00092 ros::Subscriber control_sub_;
00093 ros::Subscriber control_mav_comm_sub_;
00094
00095
00096 ros::ServiceServer motor_srv_;
00097 ros::ServiceServer crtl_srv_;
00098
00099 static const double kDefaultMaxRCChannelValue = 4080;
00100
00101
00102 void processImuData(uint8_t * buf, uint32_t bufLength);
00103 void processGpsData(uint8_t * buf, uint32_t bufLength);
00104 void processRcData(uint8_t * buf, uint32_t bufLength);
00105 void processStatusData(uint8_t * buf, uint32_t bufLength);
00106 void processTimeSyncData(uint8_t * buf, uint32_t bufLength);
00107 void processPoseEKFData(uint8_t * buf, uint32_t bufLength);
00108 void processMagData(uint8_t * buf, uint32_t bufLength);
00109
00111 bool cbMotors(asctec_hl_comm::mav_ctrl_motors::Request &req, asctec_hl_comm::mav_ctrl_motors::Response &resp);
00112
00114 bool cbCtrl(asctec_hl_comm::MavCtrlSrv::Request & req, asctec_hl_comm::MavCtrlSrv::Response & resp);
00115
00120 void controlCmdCallback(const asctec_hl_comm::mav_ctrlConstPtr &msg);
00121
00127 void controlCmdCallbackMavComm(const mav_msgs::RollPitchYawrateThrustConstPtr &msg);
00128
00130 void sendControlCmd(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00131
00133 void sendAccCommandLL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00134
00136 void sendVelCommandLL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00137
00139 void sendVelCommandHL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00140
00142 void sendPosCommandHL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00143
00144 int16_t gps_status_;
00145 int16_t gps_satellites_used_;
00146
00147 double angular_velocity_variance_;
00148 double linear_acceleration_variance_;
00149 asctec_hl_comm::mav_status status_;
00150
00152 short enable_ctrl_;
00153
00155
00159 int k_stick_;
00160
00162
00166 int k_stick_yaw_;
00167
00168
00169
00170 ReconfigureServer *reconf_srv_;
00171 void cbConfig(asctec_hl_interface::HLInterfaceConfig & config, uint32_t level);
00172 asctec_hl_interface::HLInterfaceConfig config_;
00173
00174
00175 diagnostic_updater::Updater diag_updater_;
00176 diagnostic_updater::FrequencyStatus diag_imu_freq_;
00177 double diag_imu_freq_min_;
00178 double diag_imu_freq_max_;
00179 void diagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
00180
00181 public:
00182 HLInterface(ros::NodeHandle & nh, CommPtr & comm);
00183 ~HLInterface();
00184 };
00185
00186 #endif