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 #include "ssdk_interface.h"
00033 #include "helper.h"
00034 #include <asctec_hl_comm/mav_ctrl.h>
00035
00036 SSDKInterface::SSDKInterface(ros::NodeHandle & nh, CommPtr & comm):
00037 nh_(nh),
00038 pnh_("~/ssdk"),
00039 comm_(comm),
00040 have_config_(false)
00041 {
00042 ros::NodeHandle _pnh("~");
00043 _pnh.param("frame_id", frame_id_, std::string("fcu"));
00044
00045 ROS_WARN_COND(!pnh_.hasParam("omega_0_xy"), "no ssdk parameters available, position control on the HLP will not work!");
00046
00047 pose_sub_ = nh_.subscribe("pose", 1, &SSDKInterface::cbPose, this);
00048 state_sub_ = nh_.subscribe("state", 1, &SSDKInterface::cbState, this);
00049 debug_pub_ = nh_.advertise<asctec_hl_comm::DoubleArrayStamped> ("debug", 1);
00050 pose_pub_ = nh_.advertise<geometry_msgs::PoseStamped> ("current_pose", 1);
00051
00052 config_server_ = new SSDKConfigServer(pnh_);
00053 SSDKConfigServer::CallbackType f = boost::bind(&SSDKInterface::cbSSDKConfig, this, _1, _2);
00054 config_server_->setCallback(f);
00055
00056 comm_->registerCallback(HLI_PACKET_ID_SSDK_DEBUG, &SSDKInterface::processDebugData, this);
00057 comm_->registerCallback(HLI_PACKET_ID_SSDK_STATUS, &SSDKInterface::processStatusData, this);
00058 }
00059
00060 SSDKInterface::~SSDKInterface()
00061 {
00062 delete config_server_;
00063 }
00064
00065
00066 void SSDKInterface::tfCallback()
00067 {
00068 tf::StampedTransform pose;
00069 static tf::StampedTransform last_pose;
00070 ros::Time tf_time(0);
00071 if (tf_listener_.canTransform(config_.tf_ref_frame_id, config_.tf_tracked_frame_id, tf_time))
00072 {
00073 tf_listener_.lookupTransform(config_.tf_ref_frame_id, config_.tf_tracked_frame_id, tf_time, pose);
00074
00075
00076 if (pose.getOrigin() != last_pose.getOrigin())
00077 {
00078 const tf::Vector3 & pos = pose.getOrigin();
00079 const tf::Quaternion & q = pose.getRotation();
00080 sendPoseToAP(pos.x(), pos.y(), pos.z(), tf::getYaw(q), 100);
00081 last_pose = pose;
00082 }
00083 }
00084 }
00085
00086 void SSDKInterface::cbPose(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
00087 {
00088 const geometry_msgs::Point & pos = msg->pose.pose.position;
00089 double yaw = tf::getYaw(msg->pose.pose.orientation);
00090
00091 char qual = 100;
00092
00093 for (unsigned int i = 0; i < msg->pose.covariance.size(); i++)
00094 {
00095 if (msg->pose.covariance[i] > 1)
00096 {
00097 qual = 0;
00098 }
00099 }
00100
00101 sendPoseToAP(pos.x, pos.y, pos.z, yaw, qual);
00102 }
00103
00104
00105 void SSDKInterface::sendPoseToAP(const double & x, const double & y, const double & z, const double & yaw,
00106 const unsigned char & qual)
00107 {
00108 static HLI_EXT_POSITION pose;
00109 static uint8_t count = 0;
00110
00111 pose.x = (int)(x * 1000);
00112 pose.y = (int)(y * 1000);
00113 pose.z = (int)(z * 1000);
00114 pose.heading = helper::yaw2asctec(yaw);
00115 pose.qualX = qual;
00116 pose.qualY = qual;
00117 pose.qualZ = qual;
00118
00119 pose.vX = 0;
00120 pose.vY = 0;
00121 pose.vZ = 0;
00122 pose.qualVx = 0;
00123 pose.qualVy = 0;
00124 pose.qualVz = 0;
00125
00126 pose.bitfield = 0;
00127
00128 pose.count = count++;
00129
00130 comm_->sendPacket(HLI_PACKET_ID_POSITION_UPDATE, pose);
00131 }
00132
00133
00134 void SSDKInterface::cbSSDKConfig(asctec_hl_interface::SSDKConfig & config, uint32_t level)
00135 {
00136 config.p31 = config.omega_0_xy * config.omega_0_xy;
00137 config.p32 = config.omega_0_z * config.omega_0_z;
00138 config.p33 = config.omega_0_xy * config.zeta_xy * 2.0;
00139 config.p34 = config.omega_0_z * config.zeta_z * 2.0;
00140
00141 if (level & asctec_hl_interface::SSDK_SEND_PARAMETERS)
00142 {
00143 if(!sendParameters(config)){
00144
00145 ROS_FATAL("Could not send SSDK parameters to the HLP! Shutting down the node");
00146 ros::shutdown();
00147 }
00148 config.send = false;
00149 }
00150
00151 if (level & asctec_hl_interface::SSDK_TF_CHANGED)
00152 {
00153 if(tf_callback_.connected())
00154 {
00155 tf_listener_.removeTransformsChangedListener(tf_callback_);
00156 }
00157 }
00158
00159 config_ = config;
00160 have_config_ = true;
00161
00162 if ((level & asctec_hl_interface::SSDK_TF_CHANGED) && config.listen_on_tf)
00163 {
00164 if(!tf_callback_.connected())
00165 tf_callback_ = tf_listener_.addTransformsChangedListener(boost::bind(&SSDKInterface::tfCallback, this));
00166 }
00167 }
00168
00169
00170 void SSDKInterface::cbState(const sensor_fusion_comm::ExtStatePtr & msg)
00171 {
00172
00173
00174
00175
00176
00177 HLI_EXT_POSITION state;
00178
00179 double yaw = tf::getYaw(msg->pose.orientation);
00180
00181 char qual = 100;
00182
00183 state.x = static_cast<int> (msg->pose.position.x * 1000);
00184 state.y = static_cast<int> (msg->pose.position.y * 1000);
00185 state.z = static_cast<int> (msg->pose.position.z * 1000);
00186 state.heading = static_cast<int> (helper::yaw2asctec(yaw));
00187 state.qualX = qual;
00188 state.qualY = qual;
00189 state.qualZ = qual;
00190
00191 state.vX = static_cast<short> (msg->velocity.x * 1000);
00192 state.vY = static_cast<short> (msg->velocity.y * 1000);
00193 state.vZ = static_cast<short> (msg->velocity.z * 1000);
00194 state.qualVx = qual;
00195 state.qualVy = qual;
00196 state.qualVz = qual;
00197
00198 state.bitfield = EXT_POSITION_BYPASS_FILTER;
00199
00200 comm_->sendPacket(HLI_PACKET_ID_POSITION_UPDATE, state);
00201 }
00202
00203
00204 void SSDKInterface::processStatusData(uint8_t * buf, uint32_t length)
00205 {
00206 HLI_SSDK_STATUS *status = (HLI_SSDK_STATUS*)buf;
00207 if(status->have_parameters == 0 && have_config_)
00208 sendParameters(config_);
00209 }
00210
00211
00212 void SSDKInterface::processDebugData(uint8_t * buf, uint32_t length)
00213 {
00214 static unsigned int seq = 0;
00215 HLI_SSDK_DEBUG *data = (HLI_SSDK_DEBUG*)buf;
00216 int size = sizeof(HLI_SSDK_DEBUG) / sizeof(short);
00217
00218 if (pose_pub_.getNumSubscribers() > 0)
00219 {
00220
00221
00222 geometry_msgs::PoseStampedPtr msg(new geometry_msgs::PoseStamped);
00223
00224 msg->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00225 msg->header.frame_id = frame_id_;
00226 msg->header.seq = seq;
00227
00228 msg->pose.position.x = helper::debug2Double(data->debug14);
00229 msg->pose.position.y = -helper::debug2Double(data->debug15);
00230 msg->pose.position.z = -helper::debug2Double(data->debug16);
00231
00232 geometry_msgs::Quaternion & q = msg->pose.orientation;
00233 helper::angle2quaternion(helper::debug2Double(data->debug29), -helper::debug2Double(data->debug30),
00234 -helper::debug2Double(data->debug31), &q.w, &q.x, &q.y, &q.z);
00235 pose_pub_.publish(msg);
00236 }
00237
00238 if (debug_pub_.getNumSubscribers() > 0)
00239 {
00240 asctec_hl_comm::DoubleArrayStampedPtr msg(new asctec_hl_comm::DoubleArrayStamped);
00241
00242 msg->data.resize(size);
00243
00244 msg->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00245 msg->header.frame_id = frame_id_;
00246 msg->header.seq = seq;
00247
00248 msg->data[0] = helper::debug2Double(data->debug01);
00249 msg->data[1] = helper::debug2Double(data->debug02);
00250 msg->data[2] = helper::debug2Double(data->debug03);
00251 msg->data[3] = helper::debug2Double(data->debug04);
00252 msg->data[4] = helper::debug2Double(data->debug05);
00253 msg->data[5] = helper::debug2Double(data->debug06);
00254 msg->data[6] = helper::debug2Double(data->debug07);
00255 msg->data[7] = helper::debug2Double(data->debug08);
00256 msg->data[8] = helper::debug2Double(data->debug09);
00257 msg->data[9] = helper::debug2Double(data->debug10);
00258 msg->data[10] = helper::debug2Double(data->debug11);
00259 msg->data[11] = helper::debug2Double(data->debug12);
00260 msg->data[12] = helper::debug2Double(data->debug13);
00261 msg->data[13] = helper::debug2Double(data->debug14);
00262 msg->data[14] = helper::debug2Double(data->debug15);
00263 msg->data[15] = helper::debug2Double(data->debug16);
00264 msg->data[16] = helper::debug2Double(data->debug17);
00265 msg->data[17] = helper::debug2Double(data->debug18);
00266 msg->data[18] = helper::debug2Double(data->debug19);
00267 msg->data[19] = helper::debug2Double(data->debug20);
00268 msg->data[20] = helper::debug2Double(data->debug21);
00269 msg->data[21] = helper::debug2Double(data->debug22);
00270 msg->data[22] = helper::debug2Double(data->debug23);
00271 msg->data[23] = helper::debug2Double(data->debug24);
00272 msg->data[24] = helper::debug2Double(data->debug25);
00273 msg->data[25] = helper::debug2Double(data->debug26);
00274 msg->data[26] = helper::debug2Double(data->debug27);
00275 msg->data[27] = helper::debug2Double(data->debug28);
00276 msg->data[28] = helper::debug2Double(data->debug29);
00277 msg->data[29] = helper::debug2Double(data->debug30);
00278 msg->data[30] = helper::debug2Double(data->debug31);
00279 msg->data[31] = helper::debug2Double(data->debug32);
00280 msg->data[32] = helper::debug2Double(data->debug33);
00281 msg->data[33] = helper::debug2Double(data->debug34);
00282 msg->data[34] = helper::debug2Double(data->debug35);
00283 msg->data[35] = helper::debug2Double(data->debug36);
00284 msg->data[36] = helper::debug2Double(data->debug37);
00285 msg->data[37] = helper::debug2Double(data->debug38);
00286 msg->data[38] = helper::debug2Double(data->debug39);
00287
00288 debug_pub_.publish(msg);
00289 }
00290 seq++;
00291 }
00292
00293 bool SSDKInterface::sendParameters(const asctec_hl_interface::SSDKConfig & config)
00294 {
00295 HLI_SSDK_PARAMS params;
00296 params.p01 = helper::param2Fixpoint(config.p1);
00297 params.p02 = helper::param2Fixpoint(config.p2);
00298 params.p03 = helper::param2Fixpoint(config.p3);
00299 params.p04 = helper::param2Fixpoint(config.p4);
00300 params.p05 = helper::param2Fixpoint(config.p5);
00301 params.p06 = helper::param2Fixpoint(config.p6);
00302 params.p07 = helper::param2Fixpoint(config.p7);
00303 params.p08 = helper::param2Fixpoint(config.p8);
00304 params.p09 = helper::param2Fixpoint(config.p9);
00305 params.p10 = helper::param2Fixpoint(config.p10);
00306 params.p11 = helper::param2Fixpoint(config.p11);
00307 params.p12 = helper::param2Fixpoint(config.p12);
00308 params.p13 = helper::param2Fixpoint(config.p13);
00309 params.p14 = helper::param2Fixpoint(config.p14);
00310 params.p15 = helper::param2Fixpoint(config.p15);
00311 params.p16 = helper::param2Fixpoint(config.p16);
00312 params.p17 = helper::param2Fixpoint(config.p17);
00313 params.p18 = helper::param2Fixpoint(config.p18);
00314 params.p19 = helper::param2Fixpoint(config.p19);
00315 params.p20 = helper::param2Fixpoint(config.p20);
00316 params.p21 = helper::param2Fixpoint(config.p21);
00317 params.p22 = helper::param2Fixpoint(config.p22);
00318 params.p23 = helper::param2Fixpoint(config.p23);
00319 params.p24 = helper::param2Fixpoint(config.p24);
00320 params.p25 = helper::param2Fixpoint(config.p25);
00321 params.p26 = helper::param2Fixpoint(config.p26);
00322 params.p27 = helper::param2Fixpoint(config.p27);
00323 params.p28 = helper::param2Fixpoint(config.p28);
00324 params.p29 = helper::param2Fixpoint(config.p29);
00325 params.p30 = helper::param2Fixpoint(config.p30);
00326 params.p31 = helper::param2Fixpoint(config.p31);
00327 params.p32 = helper::param2Fixpoint(config.p32);
00328 params.p33 = helper::param2Fixpoint(config.p33);
00329 params.p34 = helper::param2Fixpoint(config.p34);
00330 params.p35 = helper::param2Fixpoint(config.p35);
00331 params.p36 = helper::param2Fixpoint(config.p36);
00332 params.p37 = helper::param2Fixpoint(config.p37);
00333 params.p38 = helper::param2Fixpoint(config.p38);
00334 params.p39 = helper::param2Fixpoint(config.p39);
00335 params.p40 = helper::param2Fixpoint(config.p40);
00336 params.p41 = helper::param2Fixpoint(config.p41);
00337 params.p42 = helper::param2Fixpoint(config.p42);
00338 params.p43 = helper::param2Fixpoint(config.p43);
00339 params.p44 = helper::param2Fixpoint(config.p44);
00340 params.p45 = helper::param2Fixpoint(config.p45);
00341 params.p46 = helper::param2Fixpoint(config.p46);
00342 params.p47 = helper::param2Fixpoint(config.p47);
00343 params.p48 = helper::param2Fixpoint(config.p48);
00344 params.p49 = helper::param2Fixpoint(config.p49);
00345 params.p50 = helper::param2Fixpoint(config.p50);
00346
00347 for(int i=0; i<5; i++){
00348 if(comm_->sendPacketAck(HLI_PACKET_ID_SSDK_PARAMETERS, params)){
00349 ROS_INFO("sent SSDK parameters");
00350 return true;
00351 }
00352 }
00353
00354 ROS_ERROR("sending SSDK parameters failed, tried 5 times");
00355 return false;
00356 }