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 "hl_interface.h"
00033 #include "helper.h"
00034 #include <asctec_hl_comm/MotorSpeed.h>
00035
00036 HLInterface::HLInterface(ros::NodeHandle & nh, CommPtr & comm) :
00037 nh_(nh), pnh_("~/fcu"), comm_(comm), gps_status_(sensor_msgs::NavSatStatus::STATUS_NO_FIX), gps_satellites_used_(0),
00038 diag_updater_(), diag_imu_freq_(diagnostic_updater::FrequencyStatusParam(&diag_imu_freq_min_,
00039 &diag_imu_freq_max_, 0, 5))
00040 {
00041 pnh_.param("frame_id", frame_id_, std::string("fcu"));
00042 pnh_.param("k_stick", k_stick_, 25);
00043 pnh_.param("k_stick_yaw", k_stick_yaw_, 120);
00044 pnh_.param("stddev_angular_velocity", angular_velocity_variance_, 0.013);
00045 pnh_.param("stddev_linear_acceleration", linear_acceleration_variance_, 0.083);
00046 pnh_.param("mav_type", mav_type_, std::string("firefly"));
00047 angular_velocity_variance_ *= angular_velocity_variance_;
00048 linear_acceleration_variance_ *= linear_acceleration_variance_;
00049
00050 pressure_height_pub_ = nh_.advertise<geometry_msgs::PointStamped> ("pressure_height", 1);
00051 imu_ros_pub_ = nh_.advertise<sensor_msgs::Imu> ("imu", 1);
00052 motors_pub_ = nh_.advertise<asctec_hl_comm::MotorSpeed> ("motor_speed", 1);
00053 gps_pub_ = nh_.advertise<sensor_msgs::NavSatFix> ("gps", 1);
00054 gps_custom_pub_ = nh_.advertise<asctec_hl_comm::GpsCustom> ("gps_custom", 1);
00055 rc_pub_ = nh_.advertise<asctec_hl_comm::mav_rcdata> ("rcdata", 1);
00056 rc_joy_pub_ = nh_.advertise<sensor_msgs::Joy>("rc", 1);
00057 status_pub_ = nh_.advertise<asctec_hl_comm::mav_status> ("status", 1);
00058 mag_pub_ = nh_.advertise<geometry_msgs::Vector3Stamped> ("mag", 1);
00059
00060 control_sub_ = nh_.subscribe("control", 1, &HLInterface::controlCmdCallback, this,
00061 ros::TransportHints().tcpNoDelay());
00062 control_mav_comm_sub_ = nh_.subscribe("command/roll_pitch_yawrate_thrust", 1, &HLInterface::controlCmdCallbackMavComm, this,
00063 ros::TransportHints().tcpNoDelay());
00064
00065 motor_srv_ = nh_.advertiseService("motor_control", &HLInterface::cbMotors, this);
00066 crtl_srv_ = nh_.advertiseService("control", &HLInterface::cbCtrl, this);
00067
00068 config_ = asctec_hl_interface::HLInterfaceConfig::__getDefault__();
00069
00070
00071 reconf_srv_ = new ReconfigureServer(pnh_);
00072 ReconfigureServer::CallbackType f = boost::bind(&HLInterface::cbConfig, this, _1, _2);
00073 reconf_srv_->setCallback(f);
00074
00075 diag_updater_.add("AscTec AutoPilot status", this, &HLInterface::diagnostic);
00076 diag_updater_.setHardwareID("none");
00077 diag_updater_.add(diag_imu_freq_);
00078 diag_updater_.force_update();
00079
00080
00081 comm_->registerCallback(HLI_PACKET_ID_IMU, &HLInterface::processImuData, this);
00082 comm_->registerCallback(HLI_PACKET_ID_RC, &HLInterface::processRcData, this);
00083 comm_->registerCallback(HLI_PACKET_ID_GPS, &HLInterface::processGpsData, this);
00084 comm_->registerCallback(HLI_PACKET_ID_STATUS, &HLInterface::processStatusData, this);
00085 comm_->registerCallback(HLI_PACKET_ID_TIMESYNC, &HLInterface::processTimeSyncData, this);
00086 comm_->registerCallback(HLI_PACKET_ID_MAG, &HLInterface::processMagData, this);
00087 }
00088
00089 HLInterface::~HLInterface()
00090 {
00091 delete reconf_srv_;
00092 }
00093
00094 void HLInterface::processImuData(uint8_t * buf, uint32_t bufLength)
00095 {
00096 HLI_IMU* data = (HLI_IMU*)buf;
00097 static int seq = 0;
00098 diag_imu_freq_.tick();
00099
00100 uint32_t subs_imu_ros = imu_ros_pub_.getNumSubscribers();
00101
00102 if (subs_imu_ros > 0)
00103 {
00104 double roll = helper::asctecAttitudeToSI(data->ang_roll);
00105 double pitch = helper::asctecAttitudeToSI(data->ang_pitch);
00106 double yaw = helper::asctecAttitudeToSI(data->ang_yaw);
00107
00108 if (yaw > M_PI) {
00109 yaw -= 2 * M_PI;
00110 }
00111 geometry_msgs::Quaternion q;
00112 helper::angle2quaternion(roll, pitch, yaw, &q.w, &q.x, &q.y, &q.z);
00113
00114 sensor_msgs::ImuPtr msg(new sensor_msgs::Imu);
00115
00116 msg->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00117 msg->header.seq = seq;
00118 msg->header.frame_id = frame_id_;
00119 msg->linear_acceleration.x = helper::asctecAccToSI(data->acc_x);
00120 msg->linear_acceleration.y = helper::asctecAccToSI(data->acc_y);
00121 msg->linear_acceleration.z = helper::asctecAccToSI(data->acc_z);
00122 msg->angular_velocity.x = helper::asctecOmegaToSI(data->ang_vel_roll);
00123 msg->angular_velocity.y = helper::asctecOmegaToSI(data->ang_vel_pitch);
00124 msg->angular_velocity.z = helper::asctecOmegaToSI(data->ang_vel_yaw);
00125 msg->orientation = q;
00126 helper::setDiagonalCovariance(msg->angular_velocity_covariance, angular_velocity_variance_);
00127 helper::setDiagonalCovariance(msg->linear_acceleration_covariance, linear_acceleration_variance_);
00128
00129 imu_ros_pub_.publish(msg);
00130 }
00131
00132 uint32_t subs_pressure_height = pressure_height_pub_.getNumSubscribers();
00133 if (subs_pressure_height > 0) {
00134 double height = data->height * 1.0e-3;
00135 geometry_msgs::PointStampedPtr msg(new geometry_msgs::PointStamped);
00136 msg->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00137 msg->header.seq = seq;
00138 msg->header.frame_id = frame_id_;
00139 msg->point.z = height;
00140 pressure_height_pub_.publish(msg);
00141 }
00142
00143 asctec_hl_comm::MotorSpeedPtr msg_motors (new asctec_hl_comm::MotorSpeed);
00144 msg_motors->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00145 msg_motors->header.seq = seq;
00146 msg_motors->header.frame_id = frame_id_;
00147 for(int i = 0; i<6; ++i)
00148 msg_motors->motor_speed[i] = data->motors[i];
00149
00150 motors_pub_.publish(msg_motors);
00151
00152 seq++;
00153 }
00154
00155 void HLInterface::processGpsData(uint8_t * buf, uint32_t bufLength)
00156 {
00157 HLI_GPS* data = (HLI_GPS*)buf;
00158 static int seq = 0;
00159 sensor_msgs::NavSatFixPtr gps_fix(new sensor_msgs::NavSatFix);
00160 asctec_hl_comm::GpsCustomPtr gps_custom(new asctec_hl_comm::GpsCustom);
00161
00162 gps_fix->header.stamp = ros::Time(((double)data->timestamp) * 1.0e-6);
00163 gps_fix->header.seq = seq;
00164 gps_fix->header.frame_id = frame_id_;
00165 gps_fix->latitude = static_cast<double> (data->latitude) * 1.0e-7;
00166 gps_fix->longitude = static_cast<double> (data->longitude) * 1.0e-7;
00167 gps_fix->altitude = static_cast<double> (data->height) * 1.0e-3;
00168
00169
00170 double var_h = static_cast<double> (data->horizontalAccuracy) * 1.0e-3 / 3.0;
00171 double var_v = static_cast<double> (data->verticalAccuracy) * 1.0e-3 / 3.0;
00172 var_h *= var_h;
00173 var_v *= var_v;
00174
00175 gps_fix->position_covariance[0] = var_h;
00176 gps_fix->position_covariance[4] = var_h;
00177 gps_fix->position_covariance[8] = var_v;
00178 gps_fix->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
00179
00180 gps_fix->status.service = sensor_msgs::NavSatStatus::SERVICE_GPS;
00181
00182 if (data->status & 0x01)
00183 gps_fix->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
00184 else
00185 gps_fix->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
00186
00187 gps_custom->header = gps_fix->header;
00188 gps_custom->status = gps_fix->status;
00189 gps_custom->longitude = gps_fix->longitude;
00190 gps_custom->latitude = gps_fix->latitude;
00191 gps_custom->altitude = gps_fix->altitude;
00192 gps_custom->position_covariance = gps_fix->position_covariance;
00193 gps_custom->position_covariance_type = gps_fix->position_covariance_type;
00194
00195 gps_custom->velocity_x = static_cast<double> (data->speedX) * 1.0e-3;
00196 gps_custom->velocity_y = static_cast<double> (data->speedY) * 1.0e-3;
00197
00198 gps_custom->pressure_height = static_cast<double>(data->pressure_height) * 1.0e-3;
00199
00200
00201 double var_vel = static_cast<double> (data->speedAccuracy) * 1.0e-3 / 3.0;
00202 var_vel *= var_vel;
00203 gps_custom->velocity_covariance[0] = gps_custom->velocity_covariance[3] = var_vel;
00204
00205
00206 gps_status_ = gps_fix->status.status;
00207 gps_satellites_used_ = data->numSatellites;
00208
00209 seq++;
00210 gps_pub_.publish(gps_fix);
00211 gps_custom_pub_.publish(gps_custom);
00212 }
00213
00214 void HLInterface::processRcData(uint8_t * buf, uint32_t bufLength)
00215 {
00216 HLI_RCDATA* data = (HLI_RCDATA*)buf;
00217 static int seq = 0;
00218 asctec_hl_comm::mav_rcdataPtr msg(new asctec_hl_comm::mav_rcdata);
00219
00220 msg->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00221 msg->header.frame_id = frame_id_;
00222 msg->header.seq = seq;
00223
00224 size_t n_channels = std::min(msg->channel.size(), size_t(HLI_NUMBER_RC_CHANNELS));
00225
00226 for (size_t i = 0; i < n_channels; i++)
00227 msg->channel[i] = data->channel[i];
00228
00229
00230 rc_pub_.publish(msg);
00231
00232 sensor_msgs::Joy joy_msg;
00233 joy_msg.header.stamp = ros::Time(data->timestamp * 1.0e-6);
00234 joy_msg.header.frame_id = frame_id_;
00235 joy_msg.header.seq = seq;
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248 const double half_max_rc_channel = 0.5*kDefaultMaxRCChannelValue;
00249
00250 for (size_t i = 0; i < 7; i++) {
00251 joy_msg.axes.push_back(
00252 ((double) data->channel[i] - half_max_rc_channel) / (half_max_rc_channel));
00253 }
00254
00255
00256 joy_msg.axes.at(0) *= -1.0;
00257 joy_msg.axes.at(1) *= -1.0;
00258 joy_msg.axes.at(3) *= -1.0;
00259
00260
00261
00262 joy_msg.buttons.push_back(1);
00263
00264 rc_joy_pub_.publish(joy_msg);
00265
00266 seq++;
00267 }
00268
00269 void HLInterface::processStatusData(uint8_t * buf, uint32_t bufLength)
00270 {
00271 HLI_STATUS* data = (HLI_STATUS*)buf;
00272 static int seq = 0;
00273 asctec_hl_comm::mav_statusPtr msg(new asctec_hl_comm::mav_status);
00274
00275 msg->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00276 msg->header.frame_id = frame_id_;
00277 msg->header.seq = seq;
00278
00279 msg->battery_voltage = data->battery_voltage * 0.001;
00280 msg->flight_time = data->flight_time;
00281 msg->debug1 = data->debug1;
00282 msg->debug2 = data->debug2;
00283 msg->cpu_load = data->cpu_load;
00284
00285 switch (data->motors)
00286 {
00287 case -1:
00288 msg->motor_status = "off";
00289 break;
00290 case 0:
00291 msg->motor_status = "stopping";
00292 break;
00293 case 1:
00294 msg->motor_status = "starting";
00295 break;
00296 case 2:
00297 msg->motor_status = "running";
00298 break;
00299 default:
00300 msg->motor_status = "";
00301 break;
00302 }
00303
00304 if ((data->flight_mode & 0x0F) == HLI_FLIGHTMODE_ACC)
00305 msg->flight_mode_ll = "Acc";
00306 else if ((data->flight_mode & 0x0F) == HLI_FLIGHTMODE_HEIGHT)
00307 msg->flight_mode_ll = "Height";
00308 else if ((data->flight_mode & 0x0F) == HLI_FLIGHTMODE_GPS)
00309 msg->flight_mode_ll = "GPS";
00310 else
00311 msg->flight_mode_ll = "unknown";
00312
00313 msg->serial_interface_enabled = data->flight_mode & HLI_SERIALINTERFACE_ENABLED_BIT;
00314 msg->serial_interface_active = data->flight_mode & HLI_SERIALINTERFACE_ACTIVE_BIT;
00315
00316 switch (gps_status_)
00317 {
00318 case sensor_msgs::NavSatStatus::STATUS_NO_FIX:
00319 msg->gps_status = "GPS no fix";
00320 break;
00321 case sensor_msgs::NavSatStatus::STATUS_FIX:
00322 msg->gps_status = "GPS fix";
00323 break;
00324 case sensor_msgs::NavSatStatus::STATUS_SBAS_FIX:
00325 msg->gps_status = "SBAS fix";
00326 break;
00327 case sensor_msgs::NavSatStatus::STATUS_GBAS_FIX:
00328 msg->gps_status = "GBAS fix";
00329 break;
00330 default:
00331 msg->gps_status = "";
00332 break;
00333 }
00334
00335 msg->gps_num_satellites = gps_satellites_used_;
00336
00337 msg->have_SSDK_parameters = data->have_SSDK_parameters == 1;
00338
00339 switch (data->state_estimation)
00340 {
00341 case HLI_MODE_STATE_ESTIMATION_EXT:
00342 msg->state_estimation = asctec_hl_interface::HLInterface_STATE_EST_EXTERN;
00343 break;
00344 case HLI_MODE_STATE_ESTIMATION_HL_EKF:
00345 msg->state_estimation = asctec_hl_interface::HLInterface_STATE_EST_HIGHLEVEL_EKF;
00346 break;
00347 case HLI_MODE_STATE_ESTIMATION_HL_SSDK:
00348 msg->state_estimation = asctec_hl_interface::HLInterface_STATE_EST_HIGHLEVEL_SSDK;
00349 break;
00350 case HLI_MODE_STATE_ESTIMATION_OFF:
00351 msg->state_estimation = asctec_hl_interface::HLInterface_STATE_EST_OFF;
00352 break;
00353 default:
00354 msg->state_estimation = "unknown";
00355 break;
00356 }
00357
00358 switch (data->position_control)
00359 {
00360 case HLI_MODE_POSCTRL_HL:
00361 msg->position_control = asctec_hl_interface::HLInterface_POSCTRL_HIGHLEVEL;
00362 break;
00363 case HLI_MODE_POSCTRL_LL:
00364 msg->position_control = asctec_hl_interface::HLInterface_POSCTRL_GPS;
00365 break;
00366 case HLI_MODE_POSCTRL_OFF:
00367 msg->position_control = asctec_hl_interface::HLInterface_POSCTRL_OFF;
00368 break;
00369 default:
00370 msg->position_control = "unknown";
00371 break;
00372 }
00373
00374 msg->rx_packets = comm_->getRxPackets();
00375 msg->rx_packets_good = comm_->getRxPacketsGood();
00376 msg->tx_packets = data->rx_packets;
00377 msg->tx_packets_good = data->rx_packets_good;
00378
00379 msg->timesync_offset = (float)data->timesync_offset * 1e-6;
00380
00381 seq++;
00382 status_ = *msg;
00383 status_pub_.publish(msg);
00384
00385 diag_updater_.update();
00386 }
00387
00388
00389 void HLInterface::diagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat)
00390 {
00391 unsigned char summary_level = diagnostic_msgs::DiagnosticStatus::OK;
00392 std::string summary_message = "OK";
00393
00394
00395
00396 if (status_.battery_voltage < (config_.battery_warning - 0.5))
00397 {
00398 summary_level = diagnostic_msgs::DiagnosticStatus::ERROR;
00399 summary_message = "battery voltage critical - land now !!!";
00400 ROS_ERROR_STREAM_THROTTLE(1, "" << summary_message << ": " << status_.battery_voltage << " V");
00401 }
00402 else if (status_.battery_voltage < config_.battery_warning)
00403 {
00404 summary_level = diagnostic_msgs::DiagnosticStatus::WARN;
00405 summary_message = "battery voltage low";
00406 ROS_WARN_STREAM_THROTTLE(1, "" << summary_message << ": " << status_.battery_voltage << " V");
00407 }
00408
00409 stat.summary(summary_level, summary_message);
00410 stat.add("Battery voltage [V]", status_.battery_voltage);
00411 stat.add("Flight time [s]", status_.flight_time);
00412 stat.add("HLP cpu load [%]", status_.cpu_load);
00413 stat.add("Position control mode", status_.position_control);
00414 stat.add("State estimation mode", status_.state_estimation);
00415 stat.add("GPS status", status_.gps_status);
00416 stat.add("GPS # satellites", status_.gps_num_satellites);
00417 stat.add("Flight mode LLP", status_.flight_mode_ll);
00418 stat.add("Motor status", status_.motor_status);
00419 stat.add("Successful TX packets [%]", (float)status_.tx_packets_good/(float)status_.tx_packets*100.0);
00420 stat.add("Successful RX packets [%]", (float)status_.rx_packets_good/(float)status_.rx_packets*100.0);
00421 stat.add("Serial interface enabled", static_cast<bool>(status_.serial_interface_enabled));
00422 stat.add("Serial interface active", static_cast<bool>(status_.serial_interface_active));
00423 stat.add("Have SSDK parameters", static_cast<bool>(status_.have_SSDK_parameters));
00424 stat.add("Timesync offset [ms]", status_.timesync_offset*1000.0);
00425 stat.add("Debug 1", status_.debug1);
00426 stat.add("Debug 2", status_.debug2);
00427 }
00428
00429 void HLInterface::processTimeSyncData(uint8_t * buf, uint32_t bufLength)
00430 {
00431 HLI_TIMESYNC data = *(HLI_TIMESYNC*)buf;
00432
00433 data.ts1 = (uint64_t)(ros::Time::now().toSec() * 1.0e6);
00434
00435 comm_->sendPacket(HLI_PACKET_ID_TIMESYNC, data);
00436
00437
00438 ROS_WARN_STREAM_COND(std::abs(status_.timesync_offset) > 0.002, "imu time is off by "<<status_.timesync_offset * 1e3 <<" ms");
00439 }
00440
00441 void HLInterface::processMagData(uint8_t * buf, uint32_t bufLength)
00442 {
00443 HLI_MAG* data = (HLI_MAG*)buf;
00444 static int seq = 0;
00445 geometry_msgs::Vector3StampedPtr msg(new geometry_msgs::Vector3Stamped);
00446
00447 msg->header.stamp = ros::Time(data->timestamp * 1.0e-6);
00448 msg->header.frame_id = frame_id_;
00449 msg->header.seq = seq;
00450
00451 msg->vector.x = data->x;
00452 msg->vector.y = data->y;
00453 msg->vector.z = data->z;
00454
00455 seq++;
00456 mag_pub_.publish(msg);
00457 }
00458
00459 bool HLInterface::cbMotors(asctec_hl_comm::mav_ctrl_motors::Request &req,
00460 asctec_hl_comm::mav_ctrl_motors::Response &resp)
00461 {
00462 HLI_MOTORS data;
00463
00464 if (req.startMotors)
00465 {
00466 data.motors = 1;
00467 ROS_INFO("request to start motors");
00468 }
00469 else
00470 {
00471 data.motors = 0;
00472 ROS_INFO("request to stop motors");
00473 }
00474
00475
00476 bool success = false;
00477 for (int i = 0; i < 5; i++)
00478 {
00479 success = comm_->sendPacketAck(HLI_PACKET_ID_MOTORS, data, 0.5);
00480 if (success)
00481 break;
00482 }
00483
00484 if(!success)
00485 {
00486 ROS_WARN("unable to send motor on/off command");
00487 resp.motorsRunning = status_.motor_status == "running";
00488 return false;
00489 }
00490
00491 ros::Duration d(0.1);
00492 for (int i = 0; i < 10; i++)
00493 {
00494 if (req.startMotors && status_.motor_status == "running")
00495 {
00496 resp.motorsRunning = true;
00497 return true;
00498 }
00499 else if (!req.startMotors && status_.motor_status == "off")
00500 {
00501 resp.motorsRunning = false;
00502 return true;
00503 }
00504 d.sleep();
00505 }
00506
00507 ROS_WARN("switching motors %s timed out", req.startMotors?"on":"off");
00508 return false;
00509 }
00510
00511 void HLInterface::controlCmdCallback(const asctec_hl_comm::mav_ctrlConstPtr & msg)
00512 {
00513 sendControlCmd(*msg);
00514 }
00515
00516
00517 void HLInterface::controlCmdCallbackMavComm(const mav_msgs::RollPitchYawrateThrustConstPtr & msg)
00518 {
00519 asctec_hl_comm::mav_ctrl msg_old;
00520
00521 msg_old.type = asctec_hl_comm::mav_ctrl::acceleration;
00522 msg_old.x = - msg->pitch;
00523 msg_old.y = - msg->roll;
00524 double thrust = msg->thrust.z;
00525
00526
00527
00528 double throttle = 0.0;
00529 if(mav_type_ == "hummingbird"){
00530 throttle = thrust/16.0 + 0.1;
00531 }else if(mav_type_ == "firefly"){
00532 throttle = thrust/36.0 + 0.1;
00533 }else{
00534 ROS_ERROR("Unkown vehicle type...");
00535 return;
00536 }
00537
00538 if(throttle > 0.95)
00539 throttle = 0.95;
00540
00541 if(throttle < 0)
00542 throttle = 0;
00543
00544 msg_old.z = throttle;
00545 msg_old.yaw = msg->yaw_rate;
00546
00547 sendControlCmd(msg_old);
00548 }
00549
00550
00551 bool HLInterface::cbCtrl(asctec_hl_comm::MavCtrlSrv::Request & req, asctec_hl_comm::MavCtrlSrv::Response & resp)
00552 {
00553 sendControlCmd(req.ctrl, &resp.ctrl_result);
00554 return resp.ctrl_result.type != -1;
00555 }
00556
00557 void HLInterface::sendControlCmd(const asctec_hl_comm::mav_ctrl & ctrl, asctec_hl_comm::mav_ctrl * ctrl_result)
00558 {
00559 bool validCommand = false;
00560
00561 if (ctrl.type == asctec_hl_comm::mav_ctrl::acceleration)
00562 {
00563 if(config_.position_control == asctec_hl_interface::HLInterface_POSCTRL_OFF)
00564 {
00565 sendAccCommandLL(ctrl, ctrl_result);
00566 validCommand = true;
00567 }
00568 else
00569 {
00570 ROS_WARN_STREAM_THROTTLE(2,
00571 "GPS/Highlevel position control must be turned off. "
00572 "Set \"position_control\" parameter to \"off\"");
00573 if(ctrl_result != NULL)
00574 ctrl_result->type = -1;
00575 }
00576 }
00577
00578 else if (ctrl.type == asctec_hl_comm::mav_ctrl::velocity_body)
00579 {
00580 if (config_.position_control == asctec_hl_interface::HLInterface_POSCTRL_GPS)
00581 {
00582 sendVelCommandLL(ctrl, ctrl_result);
00583 validCommand = true;
00584 }
00585 else if (config_.position_control == asctec_hl_interface::HLInterface_POSCTRL_HIGHLEVEL)
00586 {
00587 sendVelCommandHL(ctrl, ctrl_result);
00588 validCommand = true;
00589 }
00590 else
00591 {
00592 ROS_WARN_STREAM_THROTTLE(2,
00593 "Higlevel or Lowlevel processor position control has not "
00594 "been chosen. Set \"position_control\" parameter to "
00595 "\"HighLevel\" or \"GPS\" ! sending nothing to mav !");
00596 if(ctrl_result != NULL)
00597 ctrl_result->type = -1;
00598 }
00599 }
00600 else if (ctrl.type == asctec_hl_comm::mav_ctrl::velocity)
00601 {
00602 if (config_.position_control == asctec_hl_interface::HLInterface_POSCTRL_HIGHLEVEL)
00603 {
00604 sendVelCommandHL(ctrl, ctrl_result);
00605 validCommand = true;
00606 }
00607 else
00608 {
00609 ROS_WARN_STREAM_THROTTLE(2,
00610 "Higlevel or Lowlevel processor position control has not "
00611 "been chosen. Set \"position_control\" parameter to "
00612 "\"HighLevel\" ! sending nothing to mav !");
00613 if(ctrl_result != NULL)
00614 ctrl_result->type = -1;
00615 }
00616 }
00617 else if (ctrl.type == asctec_hl_comm::mav_ctrl::position || ctrl.type == asctec_hl_comm::mav_ctrl::position_body)
00618 {
00619
00620 asctec_hl_comm::mav_ctrl ctrl_msg = ctrl;
00621 if(ctrl_msg.v_max_xy == -1)
00622 ctrl_msg.v_max_xy = config_.max_velocity_xy;
00623
00624 if(ctrl_msg.v_max_z == -1)
00625 ctrl_msg.v_max_z = config_.max_velocity_z;
00626
00627 if (config_.position_control == asctec_hl_interface::HLInterface_POSCTRL_HIGHLEVEL &&
00628 config_.state_estimation != asctec_hl_interface::HLInterface_STATE_EST_OFF)
00629 {
00630 sendPosCommandHL(ctrl_msg, ctrl_result);
00631 validCommand = true;
00632 }
00633 else
00634 {
00635 ROS_WARN_STREAM_THROTTLE(2,
00636 "Higlevel processor position control was not chosen and/or no state "
00637 "estimation was selected. Set the \"position_control\" parameter to "
00638 "\"HighLevel\" and the \"state_estimation\" parameter to anything but \"off\"! sending nothing to mav !");
00639 if(ctrl_result != NULL)
00640 ctrl_result->type = -1;
00641 }
00642 }
00643
00644
00645 if (!validCommand)
00646 {
00647 ROS_WARN_STREAM_THROTTLE(2,"Control type was not specified ... not sending anything to the mav");
00648 }
00649 }
00650
00651 void HLInterface::sendAccCommandLL(const asctec_hl_comm::mav_ctrl & msg, asctec_hl_comm::mav_ctrl * ctrl_result)
00652 {
00653 HLI_CMD_LL ctrlLL;
00654
00655
00656 ctrlLL.x = helper::clamp<short>(-2047, 2047, (short)(msg.x * 180.0 / M_PI * 1000.0 / (float)k_stick_));
00657 ctrlLL.y = helper::clamp<short>(-2047, 2047, (short)(msg.y * 180.0 / M_PI * 1000.0 / (float)k_stick_));
00658
00659
00660
00661 ctrlLL.yaw = helper::clamp<short>(-1700, 1700, (short)(msg.yaw * 180.0 / M_PI * 1000.0 / (float)k_stick_yaw_));
00662
00663
00664 if (msg.z > 1.0)
00665 {
00666 ROS_ERROR(
00667 "I just prevented you from giving full thrust..."
00668 "\nset the input range correct!!! [0 ... 1.0] ");
00669
00670 if(ctrl_result != NULL)
00671 ctrl_result->type = -1;
00672
00673 return;
00674 }
00675 else
00676 {
00677 ctrlLL.z = helper::clamp<short>(0, 4096, (short)(msg.z * 4096.0));
00678 }
00679
00680 if(ctrl_result != NULL)
00681 {
00682 *ctrl_result = msg;
00683 ctrl_result->x = static_cast<float>(ctrlLL.x * k_stick_) / 180.0 * M_PI * 1e-3;
00684 ctrl_result->y = static_cast<float>(ctrlLL.y * k_stick_) / 180.0 * M_PI * 1e-3;
00685 ctrl_result->z = static_cast<float>(ctrlLL.z) / 4096.0;
00686 ctrl_result->yaw = static_cast<float>(ctrlLL.yaw * k_stick_yaw_) / 180.0 * M_PI * 1e-3;
00687 }
00688
00689
00690 comm_->sendPacket(HLI_PACKET_ID_CONTROL_LL, ctrlLL);
00691 }
00692
00693 void HLInterface::sendVelCommandLL(const asctec_hl_comm::mav_ctrl & msg, asctec_hl_comm::mav_ctrl * ctrl_result)
00694 {
00695 HLI_CMD_LL ctrlLL;
00696
00697 ctrlLL.x = helper::clamp<short>(-2047, 2047, (short)(msg.x / config_.max_velocity_xy * 2047.0));
00698 ctrlLL.y = helper::clamp<short>(-2047, 2047, (short)(msg.y / config_.max_velocity_xy * 2047.0));
00699 ctrlLL.yaw = helper::clamp<short>(-2047, 2047, (short)(msg.yaw / config_.max_velocity_yaw* 2047.0));
00700 ctrlLL.z = helper::clamp<short>(-2047, 2047, (short)(msg.z / config_.max_velocity_z * 2047.0)) + 2047;
00701
00702 if (ctrl_result != NULL)
00703 {
00704 *ctrl_result = msg;
00705 ctrl_result->x = static_cast<float> (ctrlLL.x) / 2047.0 * config_.max_velocity_xy;
00706 ctrl_result->y = static_cast<float> (ctrlLL.y) / 2047.0 * config_.max_velocity_xy;
00707 ctrl_result->z = static_cast<float> (ctrlLL.z - 2047) / 2047.0 * config_.max_velocity_z;
00708 ctrl_result->yaw = static_cast<float> (ctrlLL.yaw) / 2047.0 * config_.max_velocity_yaw;
00709 }
00710
00711
00712 comm_->sendPacket(HLI_PACKET_ID_CONTROL_LL, ctrlLL);
00713 }
00714
00715 void HLInterface::sendVelCommandHL(const asctec_hl_comm::mav_ctrl & msg, asctec_hl_comm::mav_ctrl * ctrl_result)
00716 {
00717 HLI_CMD_HL ctrlHL;
00718
00719 ctrlHL.vX = (short)(helper::clamp<float>(-config_.max_velocity_xy, config_.max_velocity_xy, msg.x) * 1000.0);
00720 ctrlHL.vY = (short)(helper::clamp<float>(-config_.max_velocity_xy, config_.max_velocity_xy, msg.y) * 1000.0);
00721 ctrlHL.vZ = (short)(helper::clamp<float>(-config_.max_velocity_z, config_.max_velocity_z, msg.z) * 1000.0);
00722 ctrlHL.vYaw = (short)(helper::clamp<float>(-config_.max_velocity_yaw, config_.max_velocity_yaw, msg.yaw) * 180.0 / M_PI * 1000.0);
00723
00724 ctrlHL.x = 0;
00725 ctrlHL.y = 0;
00726 ctrlHL.z = 0;
00727 ctrlHL.heading = 0;
00728
00729 ctrlHL.bitfield = 1;
00730 if(msg.type == asctec_hl_comm::mav_ctrl::velocity_body)
00731 ctrlHL.bitfield |= EXT_POSITION_CMD_BODYFIXED;
00732
00733 if (ctrl_result != NULL)
00734 {
00735 *ctrl_result = msg;
00736 ctrl_result->x = static_cast<float> (ctrlHL.vX) * 1e-3;
00737 ctrl_result->y = static_cast<float> (ctrlHL.vY) * 1e-3;
00738 ctrl_result->z = static_cast<float> (ctrlHL.vZ) * 1e-3;
00739 ctrl_result->yaw = static_cast<float> (ctrlHL.vYaw) / 180.0e3 * M_PI;
00740 }
00741
00742 comm_->sendPacket(HLI_PACKET_ID_CONTROL_HL, ctrlHL);
00743 }
00744 void HLInterface::sendPosCommandHL(const asctec_hl_comm::mav_ctrl & msg, asctec_hl_comm::mav_ctrl * ctrl_result)
00745 {
00746 HLI_CMD_HL ctrlHL;
00747 static unsigned int seq = 1;
00748
00749 if (std::abs(msg.yaw) > M_PI)
00750 {
00751 ROS_WARN("yaw has to be in [-pi ... pi], got %f instead", msg.yaw);
00752 if (ctrl_result != NULL)
00753 ctrl_result->type = -1;
00754 return;
00755 }
00756
00757 ctrlHL.seq = seq;
00758 ctrlHL.vX = 0;
00759 ctrlHL.vX = 0;
00760 ctrlHL.vZ = 0;
00761
00762
00763 ctrlHL.x = static_cast<int>(helper::clamp<float>(config_.min_pos_x, config_.max_pos_x, msg.x) * 1000.0);
00764 ctrlHL.y = static_cast<int>(helper::clamp<float>(config_.min_pos_y, config_.max_pos_y, msg.y) * 1000.0);
00765 ctrlHL.z = static_cast<int>(helper::clamp<float>(config_.min_pos_z, config_.max_pos_z, msg.z) * 1000.0);
00766
00767 ctrlHL.heading = helper::yaw2asctec(msg.yaw);
00768
00769 ctrlHL.vMaxXY = static_cast<short>(std::min<float>(config_.max_velocity_xy, msg.v_max_xy)*1000);
00770 ctrlHL.vMaxZ = static_cast<short>(std::min<float>(config_.max_velocity_z, msg.v_max_z)*1000);
00771
00772 ctrlHL.bitfield = 0;
00773
00774 if(msg.type == asctec_hl_comm::mav_ctrl::position_body)
00775 ctrlHL.bitfield |= EXT_POSITION_CMD_BODYFIXED;
00776
00777 if (ctrl_result != NULL)
00778 {
00779 *ctrl_result = msg;
00780 ctrl_result->x = static_cast<float> (ctrlHL.x) * 1e-3;
00781 ctrl_result->y = static_cast<float> (ctrlHL.y) * 1e-3;
00782 ctrl_result->z = static_cast<float> (ctrlHL.z) * 1e-3;
00783 ctrl_result->yaw = static_cast<float> (ctrlHL.heading) / 180.0e3 * M_PI;
00784 if (ctrl_result->yaw > M_PI)
00785 ctrl_result->yaw -= 2 * M_PI;
00786 }
00787
00788 comm_->sendPacket(HLI_PACKET_ID_CONTROL_HL, ctrlHL);
00789 seq++;
00790 }
00791
00792 void HLInterface::cbConfig(asctec_hl_interface::HLInterfaceConfig & config, uint32_t level)
00793 {
00794
00795 if (level & asctec_hl_interface::HLInterface_HLI_CONFIG)
00796 {
00806 enable_ctrl_ = 0;
00807 if (config.enable_x)
00808 enable_ctrl_ |= 1;
00809 if (config.enable_y)
00810 enable_ctrl_ |= 1 << 1;
00811 if (config.enable_yaw)
00812 enable_ctrl_ |= 1 << 2;
00813 if (config.enable_z)
00814 enable_ctrl_ |= 1 << 3;
00815 if (config.position_control == asctec_hl_interface::HLInterface_POSCTRL_GPS)
00816 {
00817 enable_ctrl_ |= 1 << 4;
00818 enable_ctrl_ |= 1 << 5;
00819 }
00820
00821 HLI_CONFIG cfg;
00822 cfg.position_control_axis_enable = enable_ctrl_;
00823
00824 if (config.position_control == asctec_hl_interface::HLInterface_POSCTRL_HIGHLEVEL)
00825 cfg.mode_position_control = HLI_MODE_POSCTRL_HL;
00826 else if (config.position_control == asctec_hl_interface::HLInterface_POSCTRL_GPS)
00827 cfg.mode_position_control = HLI_MODE_POSCTRL_LL;
00828 else
00829 cfg.mode_position_control = HLI_MODE_POSCTRL_OFF;
00830
00831 if (config.state_estimation == asctec_hl_interface::HLInterface_STATE_EST_EXTERN)
00832 cfg.mode_state_estimation = HLI_MODE_STATE_ESTIMATION_EXT;
00833 else if (config.state_estimation == asctec_hl_interface::HLInterface_STATE_EST_HIGHLEVEL_SSDK)
00834 cfg.mode_state_estimation = HLI_MODE_STATE_ESTIMATION_HL_SSDK;
00835 else if (config.state_estimation == asctec_hl_interface::HLInterface_STATE_EST_HIGHLEVEL_EKF)
00836 cfg.mode_state_estimation = HLI_MODE_STATE_ESTIMATION_HL_EKF;
00837 else
00838 cfg.mode_state_estimation = HLI_MODE_STATE_ESTIMATION_OFF;
00839
00840 cfg.battery_warning_voltage = static_cast<uint16_t>(config.battery_warning * 1000);
00841
00842 if(!comm_->sendPacketAck(HLI_PACKET_ID_CONFIG, cfg)){
00843 config.enable_x = config_.enable_x;
00844 config.enable_y = config_.enable_y;
00845 config.enable_z = config_.enable_z;
00846 config.enable_yaw = config_.enable_yaw;
00847 config.position_control = config_.position_control;
00848 config.state_estimation = config_.state_estimation;
00849 config.battery_warning = config_.battery_warning;
00850 }
00851 }
00852
00853 if (level & asctec_hl_interface::HLInterface_PACKET_RATE)
00854 {
00855 HLI_SUBSCRIPTION ps;
00856 ps.imu = helper::rateToPeriod(config.packet_rate_imu);
00857 ps.rcdata = helper::rateToPeriod(config.packet_rate_rc);
00858 ps.gps = helper::rateToPeriod(config.packet_rate_gps);
00859 ps.ssdk_debug = helper::rateToPeriod(config.packet_rate_ssdk_debug);
00860 ps.ekf_state = helper::rateToPeriod(config.packet_rate_ekf_state);
00861 ps.mag = helper::rateToPeriod(config.packet_rate_mag);
00862
00863 diag_imu_freq_min_ = 0.95 * config.packet_rate_imu;
00864 diag_imu_freq_max_ = 1.05 * config.packet_rate_imu;
00865
00866 if(!comm_->sendPacketAck(HLI_PACKET_ID_SUBSCRIPTION, ps)){
00867 config.packet_rate_imu = config_.packet_rate_imu;
00868 config.packet_rate_rc = config_.packet_rate_rc;
00869 config.packet_rate_gps = config_.packet_rate_gps;
00870 config.packet_rate_ssdk_debug = config_.packet_rate_ssdk_debug;
00871 config.packet_rate_ekf_state = config_.packet_rate_ekf_state;
00872 config.packet_rate_mag = config_.packet_rate_mag;
00873 }
00874 }
00875
00876 config_ = config;
00877 }