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 SSDK_INTERFACE_H_
00033 #define SSDK_INTERFACE_H_
00034
00035 #include <ros/ros.h>
00036 #include <tf/transform_datatypes.h>
00037 #include <boost/thread.hpp>
00038
00039 #if ROS_VERSION_MINIMUM(1, 11, 7)
00040 #include <boost/signals2.hpp>
00041 typedef boost::signals2::connection Connection;
00042 #else
00043 #include <boost/signals.hpp>
00044 typedef boost::signals::connection Connection;
00045 #endif
00046
00047
00048 #include <tf/transform_listener.h>
00049
00050
00051 #include <asctec_hl_comm/DoubleArrayStamped.h>
00052 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00053 #include <nav_msgs/Odometry.h>
00054 #include <sensor_fusion_comm/ExtState.h>
00055
00056 #include "comm.h"
00057
00058
00059 #include <dynamic_reconfigure/server.h>
00060 #include <asctec_hl_interface/SSDKConfig.h>
00061
00062 typedef dynamic_reconfigure::Server<asctec_hl_interface::SSDKConfig> SSDKConfigServer;
00063
00065
00072 class SSDKInterface
00073 {
00074 private:
00075
00076 ros::NodeHandle nh_;
00077 ros::NodeHandle pnh_;
00078 CommPtr & comm_;
00079
00080 ros::Publisher debug_pub_;
00081 ros::Publisher pose_pub_;
00082 ros::Subscriber pose_sub_;
00083 ros::Subscriber state_sub_;
00084 ros::Subscriber odometry_sub_;
00085
00086 std::string frame_id_;
00087
00088 SSDKConfigServer *config_server_;
00089 asctec_hl_interface::SSDKConfig config_;
00090 bool have_config_;
00091
00092 tf::TransformListener tf_listener_;
00093 Connection tf_callback_;
00094
00096 void tfCallback();
00097
00099 void cbPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg);
00100
00102 void cbState(const sensor_fusion_comm::ExtStatePtr & msg);
00103
00105
00107 void cbOdometry(const nav_msgs::OdometryConstPtr& msg);
00108
00109 void sendPoseToAP(const double & x, const double & y, const double & z, const double & yaw,
00110 const unsigned char & qual);
00111
00113 bool sendParameters(const asctec_hl_interface::SSDKConfig & config);
00114 void processDebugData(uint8_t * buf, uint32_t length);
00115 void processStatusData(uint8_t * buf, uint32_t length);
00116 void cbSSDKConfig(asctec_hl_interface::SSDKConfig & config, uint32_t level);
00117
00118 public:
00119 SSDKInterface(ros::NodeHandle & nh, CommPtr & comm);
00120 ~SSDKInterface();
00121 };
00122
00123 #endif