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/mav_rcdata.h>
00041 #include <asctec_hl_comm/mav_ctrl.h>
00042 #include <asctec_hl_comm/mav_imu.h>
00043 #include <asctec_hl_comm/mav_status.h>
00044 #include <asctec_hl_comm/GpsCustom.h>
00045 #include <sensor_msgs/Imu.h>
00046 #include <sensor_msgs/NavSatFix.h>
00047 #include <geometry_msgs/Vector3Stamped.h>
00048 
00049 
00050 #include <asctec_hl_comm/MavCtrlSrv.h>
00051 #include <asctec_hl_comm/mav_ctrl_motors.h>
00052 
00053 
00054 #include <dynamic_reconfigure/server.h>
00055 #include <asctec_hl_interface/HLInterfaceConfig.h>
00056 
00057 typedef dynamic_reconfigure::Server<asctec_hl_interface::HLInterfaceConfig> ReconfigureServer;
00058 
00059 #include <diagnostic_updater/diagnostic_updater.h>
00060 #include <diagnostic_updater/update_functions.h>
00061 
00062 
00063 
00064 
00065 
00066 
00067 class HLInterface
00068 {
00069 private:
00070 
00071   ros::NodeHandle nh_;
00072   ros::NodeHandle pnh_;
00073   CommPtr & comm_;
00074 
00075   std::string frame_id_;
00076 
00077   ros::Publisher gps_pub_;
00078   ros::Publisher gps_custom_pub_;
00079   ros::Publisher imu_ros_pub_; 
00080   ros::Publisher imu_pub_; 
00081   ros::Publisher rc_pub_;
00082   ros::Publisher status_pub_;
00083   ros::Publisher mag_pub_;
00084   ros::Subscriber control_sub_;
00085 
00086   ros::ServiceServer motor_srv_;
00087   ros::ServiceServer crtl_srv_;
00088 
00089   
00090   void processImuData(uint8_t * buf, uint32_t bufLength);
00091   void processGpsData(uint8_t * buf, uint32_t bufLength);
00092   void processRcData(uint8_t * buf, uint32_t bufLength);
00093   void processStatusData(uint8_t * buf, uint32_t bufLength);
00094   void processTimeSyncData(uint8_t * buf, uint32_t bufLength);
00095   void processPoseEKFData(uint8_t * buf, uint32_t bufLength);
00096   void processMagData(uint8_t * buf, uint32_t bufLength);
00097 
00099   bool cbMotors(asctec_hl_comm::mav_ctrl_motors::Request &req, asctec_hl_comm::mav_ctrl_motors::Response &resp);
00100 
00102   bool cbCtrl(asctec_hl_comm::MavCtrlSrv::Request & req, asctec_hl_comm::MavCtrlSrv::Response & resp);
00103 
00108   void controlCmdCallback(const asctec_hl_comm::mav_ctrlConstPtr &msg);
00109 
00111   void sendControlCmd(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00112 
00114   void sendAccCommandLL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00115 
00117   void sendVelCommandLL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00118 
00120   void sendVelCommandHL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00121 
00123   void sendPosCommandHL(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result=NULL);
00124 
00125   int16_t gps_status_;
00126   int16_t gps_satellites_used_;
00127 
00128   double angular_velocity_variance_;
00129   double linear_acceleration_variance_;
00130   asctec_hl_comm::mav_status status_;
00131 
00133   short enable_ctrl_;
00134 
00136 
00140   int k_stick_;
00141 
00143 
00147   int k_stick_yaw_;
00148 
00149 
00150   
00151   ReconfigureServer *reconf_srv_;
00152   void cbConfig(asctec_hl_interface::HLInterfaceConfig & config, uint32_t level);
00153   asctec_hl_interface::HLInterfaceConfig config_;
00154 
00155   
00156   diagnostic_updater::Updater diag_updater_;
00157   diagnostic_updater::FrequencyStatus diag_imu_freq_;
00158   double diag_imu_freq_min_;
00159   double diag_imu_freq_max_;
00160   void diagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
00161 
00162 public:
00163   HLInterface(ros::NodeHandle & nh, CommPtr & comm);
00164   ~HLInterface();
00165 };
00166 
00167 #endif