rosflight_io.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
36 #ifdef ROSFLIGHT_VERSION
37 #define STRINGIFY(x) #x
38 #define TOSTRING(x) STRINGIFY(x) // Somehow, C++ requires two macros to convert a macro to a string
39 #define GIT_VERSION_STRING TOSTRING(ROSFLIGHT_VERSION)
40 #endif
41 
45 #include <rosflight/ros_logger.h>
46 #include <rosflight/ros_time.h>
47 #include <tf/tf.h>
48 #include <cstdint>
49 #include <eigen3/Eigen/Core>
50 #include <eigen3/Eigen/Dense>
51 #include <string>
52 
53 #include <rosflight/rosflight_io.h>
54 
55 namespace rosflight_io
56 {
58 {
61  extatt_sub_ = nh_.subscribe("external_attitude", 1, &rosflightIO::externalAttitudeCallback, this);
62 
63  unsaved_params_pub_ = nh_.advertise<std_msgs::Bool>("unsaved_params", 1, true);
64  error_pub_ = nh_.advertise<rosflight_msgs::Error>("rosflight_errors", 5,
65  true); // A relatively large queue so all messages get through
66 
72  nh_.advertiseService("param_load_from_file", &rosflightIO::paramLoadFromFileCallback, this);
77  nh_.advertiseService("reboot_to_bootloader", &rosflightIO::rebootToBootloaderSrvCallback, this);
78 
79  ros::NodeHandle nh_private("~");
80 
81  if (nh_private.param<bool>("udp", false))
82  {
83  std::string bind_host = nh_private.param<std::string>("bind_host", "localhost");
84  uint16_t bind_port = (uint16_t)nh_private.param<int>("bind_port", 14520);
85  std::string remote_host = nh_private.param<std::string>("remote_host", bind_host);
86  uint16_t remote_port = (uint16_t)nh_private.param<int>("remote_port", 14525);
87 
88  ROS_INFO("Connecting over UDP to \"%s:%d\", from \"%s:%d\"", remote_host.c_str(), remote_port, bind_host.c_str(),
89  bind_port);
90 
91  mavlink_comm_ = new mavrosflight::MavlinkUDP(bind_host, bind_port, remote_host, remote_port);
92  }
93  else
94  {
95  std::string port = nh_private.param<std::string>("port", "/dev/ttyACM0");
96  int baud_rate = nh_private.param<int>("baud_rate", 921600);
97 
98  ROS_INFO("Connecting to serial port \"%s\", at %d baud", port.c_str(), baud_rate);
99 
100  mavlink_comm_ = new mavrosflight::MavlinkSerial(port, baud_rate);
101  }
102 
103  try
104  {
105  mavlink_comm_->open();
109  mavrosflight_ =
111  }
113  {
114  ROS_FATAL("%s", e.what());
115  ros::shutdown();
116  }
117 
120 
121  // request the param list
124 
125  // request version information
126  request_version();
128 
129  // initialize latched "unsaved parameters" message value
130  std_msgs::Bool unsaved_msg;
131  unsaved_msg.data = false;
132  unsaved_params_pub_.publish(unsaved_msg);
133 
134  // Set up a few other random things
135  frame_id_ = nh_private.param<std::string>("frame_id", "world");
136 
137  prev_status_.armed = false;
138  prev_status_.failsafe = false;
139  prev_status_.rc_override = false;
140  prev_status_.offboard = false;
143 
144  // Start the heartbeat
146 }
147 
149 {
150  delete mavrosflight_;
151  delete mavlink_comm_;
152 }
153 
154 void rosflightIO::handle_mavlink_message(const mavlink_message_t &msg)
155 {
156  switch (msg.msgid)
157  {
160  break;
162  handle_status_msg(msg);
163  break;
166  break;
169  break;
172  break;
175  break;
178  break;
181  break;
184  break;
187  break;
190  break;
193  break;
196  break;
199  break;
202  break;
205  break;
208  break;
210  handle_version_msg(msg);
211  break;
214  // silently ignore (handled elsewhere)
215  break;
218  break;
221  break;
222  default:
223  ROS_DEBUG("rosflight_io: Got unhandled mavlink message ID %d", msg.msgid);
224  break;
225  }
226 }
227 
228 void rosflightIO::on_new_param_received(std::string name, double value)
229 {
230  ROS_DEBUG("Got parameter %s with value %g", name.c_str(), value);
231 }
232 
233 void rosflightIO::on_param_value_updated(std::string name, double value)
234 {
235  ROS_INFO("Parameter %s has new value %g", name.c_str(), value);
236 }
237 
238 void rosflightIO::on_params_saved_change(bool unsaved_changes)
239 {
240  std_msgs::Bool msg;
241  msg.data = unsaved_changes;
243 
244  if (unsaved_changes)
245  {
246  ROS_WARN_THROTTLE(1, "There are unsaved changes to onboard parameters");
247  }
248  else
249  {
250  ROS_INFO("Onboard parameters have been saved");
251  }
252 }
253 
254 void rosflightIO::handle_heartbeat_msg(const mavlink_message_t &msg)
255 {
256  ROS_INFO_ONCE("Got HEARTBEAT, connected.");
257 }
258 
259 void rosflightIO::handle_status_msg(const mavlink_message_t &msg)
260 {
261  mavlink_rosflight_status_t status_msg;
262  mavlink_msg_rosflight_status_decode(&msg, &status_msg);
263 
264  // armed state check
265  if (prev_status_.armed != status_msg.armed)
266  {
267  if (status_msg.armed)
268  ROS_WARN("Autopilot ARMED");
269  else
270  ROS_WARN("Autopilot DISARMED");
271  }
272 
273  // failsafe check
274  if (prev_status_.failsafe != status_msg.failsafe)
275  {
276  if (status_msg.failsafe)
277  ROS_ERROR("Autopilot FAILSAFE");
278  else
279  ROS_INFO("Autopilot FAILSAFE RECOVERED");
280  }
281 
282  // rc override check
283  if (prev_status_.rc_override != status_msg.rc_override)
284  {
285  if (status_msg.rc_override)
286  ROS_WARN("RC override active");
287  else
288  ROS_WARN("Returned to computer control");
289  }
290 
291  // offboard control check
292  if (prev_status_.offboard != status_msg.offboard)
293  {
294  if (status_msg.offboard)
295  ROS_WARN("Computer control active");
296  else
297  ROS_WARN("Computer control lost");
298  }
299 
300  // Print if got error code
301  if (prev_status_.error_code != status_msg.error_code)
302  {
305  "IMU not responding");
308  "Unhealthy estimator");
310  "Time going backwards");
312  "Uncalibrated IMU");
314 
315  ROS_DEBUG("Autopilot ERROR 0x%02x", status_msg.error_code);
316  }
317 
318  // Print if change in control mode
319  if (prev_status_.control_mode != status_msg.control_mode)
320  {
321  std::string mode_string;
322  switch (status_msg.control_mode)
323  {
324  case MODE_PASS_THROUGH:
325  mode_string = "PASS_THROUGH";
326  break;
328  mode_string = "RATE";
329  break;
331  mode_string = "ANGLE";
332  break;
333  default:
334  mode_string = "UNKNOWN";
335  }
336  ROS_WARN_STREAM("Autopilot now in " << mode_string << " mode");
337  }
338 
339  prev_status_ = status_msg;
340 
341  // Build the status message and send it
342  rosflight_msgs::Status out_status;
343  out_status.header.stamp = ros::Time::now();
344  out_status.armed = status_msg.armed;
345  out_status.failsafe = status_msg.failsafe;
346  out_status.rc_override = status_msg.rc_override;
347  out_status.offboard = status_msg.offboard;
348  out_status.control_mode = status_msg.control_mode;
349  out_status.error_code = status_msg.error_code;
350  out_status.num_errors = status_msg.num_errors;
351  out_status.loop_time_us = status_msg.loop_time_us;
352  if (status_pub_.getTopic().empty())
353  {
354  status_pub_ = nh_.advertise<rosflight_msgs::Status>("status", 1);
355  }
356  status_pub_.publish(out_status);
357 }
358 
359 void rosflightIO::handle_command_ack_msg(const mavlink_message_t &msg)
360 {
363 
364  if (ack.success == ROSFLIGHT_CMD_SUCCESS)
365  {
366  ROS_DEBUG("MAVLink command %d Acknowledged", ack.command);
367  }
368  else
369  {
370  ROS_ERROR("MAVLink command %d Failed", ack.command);
371  }
372 }
373 
374 void rosflightIO::handle_statustext_msg(const mavlink_message_t &msg)
375 {
376  mavlink_statustext_t status;
377  mavlink_msg_statustext_decode(&msg, &status);
378 
379  // ensure null termination
381  memcpy(c_str, status.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
383 
384  switch (status.severity)
385  {
387  case MAV_SEVERITY_ALERT:
389  case MAV_SEVERITY_ERROR:
390  ROS_ERROR("[Autopilot]: %s", c_str);
391  break;
393  ROS_WARN("[Autopilot]: %s", c_str);
394  break;
395  case MAV_SEVERITY_NOTICE:
396  case MAV_SEVERITY_INFO:
397  ROS_INFO("[Autopilot]: %s", c_str);
398  break;
399  case MAV_SEVERITY_DEBUG:
400  ROS_DEBUG("[Autopilot]: %s", c_str);
401  break;
402  }
403 }
404 
405 void rosflightIO::handle_attitude_quaternion_msg(const mavlink_message_t &msg)
406 {
409 
410  rosflight_msgs::Attitude attitude_msg;
411 
412  attitude_msg.header.stamp = fcu_time_to_ros_time(std::chrono::milliseconds(attitude.time_boot_ms));
413  attitude_msg.attitude.w = attitude.q1;
414  attitude_msg.attitude.x = attitude.q2;
415  attitude_msg.attitude.y = attitude.q3;
416  attitude_msg.attitude.z = attitude.q4;
417  attitude_msg.angular_velocity.x = attitude.rollspeed;
418  attitude_msg.angular_velocity.y = attitude.pitchspeed;
419  attitude_msg.angular_velocity.z = attitude.yawspeed;
420 
421  geometry_msgs::Vector3Stamped euler_msg;
422  euler_msg.header.stamp = attitude_msg.header.stamp;
423 
424  tf::Quaternion quat(attitude.q2, attitude.q3, attitude.q4, attitude.q1);
425  tf::Matrix3x3(quat).getEulerYPR(euler_msg.vector.z, euler_msg.vector.y, euler_msg.vector.x);
426 
427  // save off the quaternion for use with the IMU callback
429 
430  if (attitude_pub_.getTopic().empty())
431  {
432  attitude_pub_ = nh_.advertise<rosflight_msgs::Attitude>("attitude", 1);
433  }
434  if (euler_pub_.getTopic().empty())
435  {
436  euler_pub_ = nh_.advertise<geometry_msgs::Vector3Stamped>("attitude/euler", 1);
437  }
438  attitude_pub_.publish(attitude_msg);
439  euler_pub_.publish(euler_msg);
440 }
441 
442 void rosflightIO::handle_small_imu_msg(const mavlink_message_t &msg)
443 {
445  mavlink_msg_small_imu_decode(&msg, &imu);
446 
447  sensor_msgs::Imu imu_msg;
448  imu_msg.header.stamp = fcu_time_to_ros_time(std::chrono::microseconds(imu.time_boot_us));
449  imu_msg.header.frame_id = frame_id_;
450  imu_msg.linear_acceleration.x = imu.xacc;
451  imu_msg.linear_acceleration.y = imu.yacc;
452  imu_msg.linear_acceleration.z = imu.zacc;
453  imu_msg.angular_velocity.x = imu.xgyro;
454  imu_msg.angular_velocity.y = imu.ygyro;
455  imu_msg.angular_velocity.z = imu.zgyro;
456  imu_msg.orientation = attitude_quat_;
457 
458  sensor_msgs::Temperature temp_msg;
459  temp_msg.header.stamp = imu_msg.header.stamp;
460  temp_msg.header.frame_id = frame_id_;
461  temp_msg.temperature = imu.temperature;
462 
463  if (imu_pub_.getTopic().empty())
464  {
465  imu_pub_ = nh_.advertise<sensor_msgs::Imu>("imu/data", 1);
466  }
467  imu_pub_.publish(imu_msg);
468 
469  if (imu_temp_pub_.getTopic().empty())
470  {
471  imu_temp_pub_ = nh_.advertise<sensor_msgs::Temperature>("imu/temperature", 1);
472  }
473  imu_temp_pub_.publish(temp_msg);
474 }
475 
476 void rosflightIO::handle_rosflight_output_raw_msg(const mavlink_message_t &msg)
477 {
480 
481  rosflight_msgs::OutputRaw out_msg;
482  out_msg.header.stamp = fcu_time_to_ros_time(std::chrono::microseconds(servo.stamp));
483  for (int i = 0; i < 14; i++)
484  {
485  out_msg.values[i] = servo.values[i];
486  }
487 
488  if (output_raw_pub_.getTopic().empty())
489  {
490  output_raw_pub_ = nh_.advertise<rosflight_msgs::OutputRaw>("output_raw", 1);
491  }
492  output_raw_pub_.publish(out_msg);
493 }
494 
495 void rosflightIO::handle_rc_channels_raw_msg(const mavlink_message_t &msg)
496 {
499 
500  rosflight_msgs::RCRaw out_msg;
501  out_msg.header.stamp = fcu_time_to_ros_time(std::chrono::milliseconds(rc.time_boot_ms));
502 
503  out_msg.values[0] = rc.chan1_raw;
504  out_msg.values[1] = rc.chan2_raw;
505  out_msg.values[2] = rc.chan3_raw;
506  out_msg.values[3] = rc.chan4_raw;
507  out_msg.values[4] = rc.chan5_raw;
508  out_msg.values[5] = rc.chan6_raw;
509  out_msg.values[6] = rc.chan7_raw;
510  out_msg.values[7] = rc.chan8_raw;
511 
512  if (rc_raw_pub_.getTopic().empty())
513  {
514  rc_raw_pub_ = nh_.advertise<rosflight_msgs::RCRaw>("rc_raw", 1);
515  }
516  rc_raw_pub_.publish(out_msg);
517 }
518 
519 void rosflightIO::handle_diff_pressure_msg(const mavlink_message_t &msg)
520 {
523 
524  rosflight_msgs::Airspeed airspeed_msg;
525  airspeed_msg.header.stamp = ros::Time::now();
526  airspeed_msg.velocity = diff.velocity;
527  airspeed_msg.differential_pressure = diff.diff_pressure;
528  airspeed_msg.temperature = diff.temperature;
529 
530  if (calibrate_airspeed_srv_.getService().empty())
531  {
533  nh_.advertiseService("calibrate_airspeed", &rosflightIO::calibrateAirspeedSrvCallback, this);
534  }
535 
536  if (diff_pressure_pub_.getTopic().empty())
537  {
538  diff_pressure_pub_ = nh_.advertise<rosflight_msgs::Airspeed>("airspeed", 1);
539  }
540  diff_pressure_pub_.publish(airspeed_msg);
541 }
542 
543 void rosflightIO::handle_named_value_int_msg(const mavlink_message_t &msg)
544 {
547 
548  // ensure null termination of name
552  std::string name(c_name);
553 
554  if (named_value_int_pubs_.find(name) == named_value_int_pubs_.end())
555  {
556  ros::NodeHandle nh;
557  named_value_int_pubs_[name] = nh.advertise<std_msgs::Int32>("named_value/int/" + name, 1);
558  }
559 
560  std_msgs::Int32 out_msg;
561  out_msg.data = val.value;
562 
563  named_value_int_pubs_[name].publish(out_msg);
564 }
565 
566 void rosflightIO::handle_named_value_float_msg(const mavlink_message_t &msg)
567 {
570 
571  // ensure null termination of name
575  std::string name(c_name);
576 
577  if (named_value_float_pubs_.find(name) == named_value_float_pubs_.end())
578  {
579  ros::NodeHandle nh;
580  named_value_float_pubs_[name] = nh.advertise<std_msgs::Float32>("named_value/float/" + name, 1);
581  }
582 
583  std_msgs::Float32 out_msg;
584  out_msg.data = val.value;
585 
586  named_value_float_pubs_[name].publish(out_msg);
587 }
588 
589 void rosflightIO::handle_named_command_struct_msg(const mavlink_message_t &msg)
590 {
593 
594  // ensure null termination of name
596  memcpy(c_name, command.name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
598  std::string name(c_name);
599 
601  {
602  ros::NodeHandle nh;
603  named_command_struct_pubs_[name] = nh.advertise<rosflight_msgs::Command>("named_value/command_struct/" + name, 1);
604  }
605 
606  rosflight_msgs::Command command_msg;
607  if (command.type == MODE_PASS_THROUGH)
611  else if (command.type == MODE_ROLL_PITCH_YAWRATE_THROTTLE)
613 
614  command_msg.ignore = command.ignore;
615  command_msg.x = command.x;
616  command_msg.y = command.y;
617  command_msg.z = command.z;
618  command_msg.F = command.F;
619  named_command_struct_pubs_[name].publish(command_msg);
620 }
621 
622 void rosflightIO::handle_small_baro_msg(const mavlink_message_t &msg)
623 {
625  mavlink_msg_small_baro_decode(&msg, &baro);
626 
627  rosflight_msgs::Barometer baro_msg;
628  baro_msg.header.stamp = ros::Time::now();
629  baro_msg.altitude = baro.altitude;
630  baro_msg.pressure = baro.pressure;
631  baro_msg.temperature = baro.temperature;
632 
633  // If we are getting barometer messages, then we should publish the barometer calibration service
634  if (calibrate_baro_srv_.getService().empty())
635  {
637  }
638 
639  if (baro_pub_.getTopic().empty())
640  {
641  baro_pub_ = nh_.advertise<rosflight_msgs::Barometer>("baro", 1);
642  }
643  baro_pub_.publish(baro_msg);
644 }
645 
646 void rosflightIO::handle_small_mag_msg(const mavlink_message_t &msg)
647 {
649  mavlink_msg_small_mag_decode(&msg, &mag);
650 
652  sensor_msgs::MagneticField mag_msg;
653  mag_msg.header.stamp = ros::Time::now(); // mavrosflight_->time.get_ros_time_us(mag.time_boot_us);
654  mag_msg.header.frame_id = frame_id_;
655 
656  mag_msg.magnetic_field.x = mag.xmag;
657  mag_msg.magnetic_field.y = mag.ymag;
658  mag_msg.magnetic_field.z = mag.zmag;
659 
660  if (mag_pub_.getTopic().empty())
661  {
662  mag_pub_ = nh_.advertise<sensor_msgs::MagneticField>("magnetometer", 1);
663  }
664  mag_pub_.publish(mag_msg);
665 }
666 
667 void rosflightIO::handle_small_range_msg(const mavlink_message_t &msg)
668 {
669  mavlink_small_range_t range;
670  mavlink_msg_small_range_decode(&msg, &range);
671 
672  sensor_msgs::Range alt_msg;
673  alt_msg.header.stamp = ros::Time::now();
674  alt_msg.max_range = range.max_range;
675  alt_msg.min_range = range.min_range;
676  alt_msg.range = range.range;
677 
678  switch (range.type)
679  {
681  alt_msg.radiation_type = sensor_msgs::Range::ULTRASOUND;
682  alt_msg.field_of_view = 1.0472; // approx 60 deg
683 
684  if (sonar_pub_.getTopic().empty())
685  {
686  sonar_pub_ = nh_.advertise<sensor_msgs::Range>("sonar", 1);
687  }
688  sonar_pub_.publish(alt_msg);
689  break;
691  alt_msg.radiation_type = sensor_msgs::Range::INFRARED;
692  alt_msg.field_of_view = .0349066; // approx 2 deg
693 
694  if (lidar_pub_.getTopic().empty())
695  {
696  lidar_pub_ = nh_.advertise<sensor_msgs::Range>("lidar", 1);
697  }
698  lidar_pub_.publish(alt_msg);
699  break;
700  default:
701  break;
702  }
703 }
704 
705 ros::Time rosflightIO::fcu_time_to_ros_time(std::chrono::nanoseconds fcu_time)
706 {
707  ros::Time now;
708  now.fromNSec(mavrosflight_->time.fcu_time_to_system_time(fcu_time).count());
709  return now;
710 }
711 
712 std::string rosflightIO::get_major_minor_version(const std::string &version)
713 {
714  size_t start_index = 0;
715  if (version[0] == 'v' || version[0] == 'V') // Skipping the 'v' prefix
716  start_index = 1;
717  size_t dot_index = version.find('.'); // index of the first dot
718  dot_index = version.find('.', dot_index + 1); // index of the second dot
719  return version.substr(start_index, dot_index - start_index);
720 }
721 
722 void rosflightIO::handle_version_msg(const mavlink_message_t &msg)
723 {
725 
727  mavlink_msg_rosflight_version_decode(&msg, &version);
728 
729  std_msgs::String version_msg;
730  version_msg.data = version.version;
731 
732  if (version_pub_.getTopic().empty())
733  {
734  version_pub_ = nh_.advertise<std_msgs::String>("version", 1, true);
735  }
736  version_pub_.publish(version_msg);
737 #ifdef GIT_VERSION_STRING // Macro so that is compiles even if git is not available
738  const std::string git_version_string = GIT_VERSION_STRING;
739  const std::string rosflight_major_minor_version = get_major_minor_version(git_version_string);
740  const std::string firmware_version(version.version);
741  const std::string firmware_major_minor_version = get_major_minor_version(firmware_version);
742  if (rosflight_major_minor_version == firmware_major_minor_version)
743  {
744  ROS_INFO("ROSflight/firmware version: %s", firmware_major_minor_version.c_str());
745  }
746  else
747  {
748  ROS_WARN("ROSflight version does not match firmware version. Errors or missing features may result");
749  ROS_WARN("ROSflight version: %s", rosflight_major_minor_version.c_str());
750  ROS_WARN("Firmware version: %s", firmware_major_minor_version.c_str());
751  }
752 
753 #else
754  ROS_WARN("Version checking unavailable. Firmware version may or may not be compatible with ROSflight version");
755  ROS_WARN("Firmware version: %s", version.version);
756 #endif
757 }
758 
759 void rosflightIO::handle_hard_error_msg(const mavlink_message_t &msg)
760 {
763  ROS_ERROR("Hard fault detected, with error code %u. The flight controller has rebooted.", error.error_code);
764  ROS_ERROR("Hard fault was at: 0x%x", error.pc);
765  if (error.doRearm)
766  {
767  ROS_ERROR("The firmware has rearmed itself.");
768  }
769  ROS_ERROR("The flight controller has rebooted %u time%s.", error.reset_count, error.reset_count > 1 ? "s" : "");
770  rosflight_msgs::Error error_msg;
771  error_msg.error_message = "A firmware error has caused the flight controller to reboot.";
772  error_msg.error_code = error.error_code;
773  error_msg.reset_count = error.reset_count;
774  error_msg.rearm = error.doRearm;
775  error_msg.pc = error.pc;
776  error_pub_.publish(error_msg);
777 }
778 void rosflightIO::handle_battery_status_msg(const mavlink_message_t &msg)
779 {
780  mavlink_rosflight_battery_status_t battery_status;
781  mavlink_msg_rosflight_battery_status_decode(&msg, &battery_status);
782  if (battery_status_pub_.getTopic().empty())
783  {
784  battery_status_pub_ = nh_.advertise<rosflight_msgs::BatteryStatus>("battery", 1);
785  }
786  rosflight_msgs::BatteryStatus battery_status_message;
787  battery_status_message.voltage = battery_status.battery_voltage;
788  battery_status_message.current = battery_status.battery_current;
789  battery_status_message.header.stamp = ros::Time::now();
790 
791  battery_status_pub_.publish(battery_status_message);
792 }
793 
794 void rosflightIO::handle_rosflight_gnss_msg(const mavlink_message_t &msg)
795 {
798 
799  ros::Time stamp = fcu_time_to_ros_time(std::chrono::microseconds(gnss.rosflight_timestamp));
800  rosflight_msgs::GNSS gnss_msg;
801  gnss_msg.header.stamp = stamp;
802  gnss_msg.header.frame_id = "ECEF";
803  gnss_msg.fix = gnss.fix_type;
804  gnss_msg.time = ros::Time(gnss.time, gnss.nanos);
805  gnss_msg.position[0] = .01 * gnss.ecef_x; //.01 for conversion from cm to m
806  gnss_msg.position[1] = .01 * gnss.ecef_y;
807  gnss_msg.position[2] = .01 * gnss.ecef_z;
808  gnss_msg.horizontal_accuracy = gnss.h_acc;
809  gnss_msg.vertical_accuracy = gnss.v_acc;
810  gnss_msg.velocity[0] = .01 * gnss.ecef_v_x; //.01 for conversion from cm/s to m/s
811  gnss_msg.velocity[1] = .01 * gnss.ecef_v_y;
812  gnss_msg.velocity[2] = .01 * gnss.ecef_v_z;
813  gnss_msg.speed_accuracy = gnss.s_acc;
814  if (gnss_pub_.getTopic().empty())
815  {
816  gnss_pub_ = nh_.advertise<rosflight_msgs::GNSS>("gnss", 1);
817  }
818  gnss_pub_.publish(gnss_msg);
819 
820  sensor_msgs::NavSatFix navsat_fix;
821  navsat_fix.header.stamp = stamp;
822  navsat_fix.header.frame_id = "LLA";
823  navsat_fix.latitude = 1e-7 * gnss.lat; // 1e-7 to convert from 100's of nanodegrees
824  navsat_fix.longitude = 1e-7 * gnss.lon; // 1e-7 to convert from 100's of nanodegrees
825  navsat_fix.altitude = .001 * gnss.height; //.001 to convert from mm to m
826  navsat_fix.position_covariance[0] = gnss.h_acc * gnss.h_acc;
827  navsat_fix.position_covariance[4] = gnss.h_acc * gnss.h_acc;
828  navsat_fix.position_covariance[8] = gnss.v_acc * gnss.v_acc;
829  navsat_fix.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
830  sensor_msgs::NavSatStatus navsat_status;
831  auto fix_type = gnss.fix_type;
832  switch (fix_type)
833  {
834  case GNSS_FIX_RTK_FLOAT:
835  case GNSS_FIX_RTK_FIXED:
836  navsat_status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
837  break;
838  case GNSS_FIX_FIX:
839  navsat_status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
840  break;
841  default:
842  navsat_status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
843  }
844  // The UBX is not configured to report which system is used, even though it supports them all
845  navsat_status.service = 1; // Report that only GPS was used, even though others may have been
846  navsat_fix.status = navsat_status;
847 
848  if (nav_sat_fix_pub_.getTopic().empty())
849  {
850  nav_sat_fix_pub_ = nh_.advertise<sensor_msgs::NavSatFix>("navsat_compat/fix", 1);
851  }
852  nav_sat_fix_pub_.publish(navsat_fix);
853 
854  geometry_msgs::TwistStamped twist_stamped;
855  twist_stamped.header.stamp = stamp;
856  // GNSS does not provide angular data
857  twist_stamped.twist.angular.x = 0;
858  twist_stamped.twist.angular.y = 0;
859  twist_stamped.twist.angular.z = 0;
860 
861  twist_stamped.twist.linear.x = .001 * gnss.vel_n; // Convert from mm/s to m/s
862  twist_stamped.twist.linear.y = .001 * gnss.vel_e;
863  twist_stamped.twist.linear.z = .001 * gnss.vel_d;
864 
865  if (twist_stamped_pub_.getTopic().empty())
866  twist_stamped_pub_ = nh_.advertise<geometry_msgs::TwistStamped>("navsat_compat/vel", 1);
867  twist_stamped_pub_.publish(twist_stamped);
868 
869  sensor_msgs::TimeReference time_ref;
870  time_ref.header.stamp = stamp;
871  time_ref.source = "GNSS";
872  time_ref.time_ref = ros::Time(gnss.time, gnss.nanos);
873 
874  if (time_reference_pub_.getTopic().empty())
875  time_reference_pub_ = nh_.advertise<sensor_msgs::TimeReference>("navsat_compat/time_reference", 1);
876 
877  time_reference_pub_.publish(time_ref);
878 }
879 
880 void rosflightIO::handle_rosflight_gnss_full_msg(const mavlink_message_t &msg)
881 {
884 
885  rosflight_msgs::GNSSFull msg_out;
886  msg_out.header.stamp = ros::Time::now();
887  msg_out.time_of_week = full.time_of_week;
888  msg_out.year = full.year;
889  msg_out.month = full.month;
890  msg_out.day = full.day;
891  msg_out.hour = full.hour;
892  msg_out.min = full.min;
893  msg_out.sec = full.sec;
894  msg_out.valid = full.valid;
895  msg_out.t_acc = full.t_acc;
896  msg_out.nano = full.nano;
897  msg_out.fix_type = full.fix_type;
898  msg_out.num_sat = full.num_sat;
899  msg_out.lon = full.lon;
900  msg_out.lat = full.lat;
901  msg_out.height = full.height;
902  msg_out.height_msl = full.height_msl;
903  msg_out.h_acc = full.h_acc;
904  msg_out.v_acc = full.v_acc;
905  msg_out.vel_n = full.vel_n;
906  msg_out.vel_e = full.vel_e;
907  msg_out.vel_d = full.vel_d;
908  msg_out.g_speed = full.g_speed;
909  msg_out.head_mot = full.head_mot;
910  msg_out.s_acc = full.s_acc;
911  msg_out.head_acc = full.head_acc;
912  msg_out.p_dop = full.p_dop;
913 
914  if (gnss_full_pub_.getTopic().empty())
915  gnss_full_pub_ = nh_.advertise<rosflight_msgs::GNSSFull>("gnss_full", 1);
916  gnss_full_pub_.publish(msg_out);
917 }
918 
919 void rosflightIO::commandCallback(rosflight_msgs::Command::ConstPtr msg)
920 {
923  OFFBOARD_CONTROL_IGNORE ignore = (OFFBOARD_CONTROL_IGNORE)msg->ignore;
924 
925  float x = msg->x;
926  float y = msg->y;
927  float z = msg->z;
928  float F = msg->F;
929 
930  switch (mode)
931  {
932  case MODE_PASS_THROUGH:
933  x = saturate(x, -1.0f, 1.0f);
934  y = saturate(y, -1.0f, 1.0f);
935  z = saturate(z, -1.0f, 1.0f);
936  F = saturate(F, 0.0f, 1.0f);
937  break;
940  F = saturate(F, 0.0f, 1.0f);
941  break;
943  break;
944  }
945 
946  mavlink_message_t mavlink_msg;
947  mavlink_msg_offboard_control_pack(1, 50, &mavlink_msg, mode, ignore, x, y, z, F);
948  mavrosflight_->comm.send_message(mavlink_msg);
949 }
950 
951 void rosflightIO::auxCommandCallback(rosflight_msgs::AuxCommand::ConstPtr msg)
952 {
953  uint8_t types[14];
954  float values[14];
955  for (int i = 0; i < 14; i++)
956  {
957  types[i] = msg->type_array[i];
958  values[i] = msg->values[i];
959  }
960  mavlink_message_t mavlink_msg;
961  mavlink_msg_rosflight_aux_cmd_pack(1, 50, &mavlink_msg, types, values);
962  mavrosflight_->comm.send_message(mavlink_msg);
963 }
964 
965 void rosflightIO::externalAttitudeCallback(geometry_msgs::Quaternion::ConstPtr msg)
966 {
967  mavlink_message_t mavlink_msg;
968  mavlink_msg_external_attitude_pack(1, 50, &mavlink_msg, msg->w, msg->x, msg->y, msg->z);
969  mavrosflight_->comm.send_message(mavlink_msg);
970 }
971 
972 bool rosflightIO::paramGetSrvCallback(rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res)
973 {
974  res.exists = mavrosflight_->param.get_param_value(req.name, &res.value);
975  return true;
976 }
977 
978 bool rosflightIO::paramSetSrvCallback(rosflight_msgs::ParamSet::Request &req, rosflight_msgs::ParamSet::Response &res)
979 {
980  res.exists = mavrosflight_->param.set_param_value(req.name, req.value);
981  return true;
982 }
983 
984 bool rosflightIO::paramWriteSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
985 {
986  res.success = mavrosflight_->param.write_params();
987  if (!res.success)
988  {
989  res.message = "Request rejected: write already in progress";
990  }
991 
992  return true;
993 }
994 
995 bool rosflightIO::paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req,
996  rosflight_msgs::ParamFile::Response &res)
997 {
998  res.success = mavrosflight_->param.save_to_file(req.filename);
999  return true;
1000 }
1001 
1002 bool rosflightIO::paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req,
1003  rosflight_msgs::ParamFile::Response &res)
1004 {
1005  res.success = mavrosflight_->param.load_from_file(req.filename);
1006  return true;
1007 }
1008 
1009 bool rosflightIO::calibrateImuBiasSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
1010 {
1011  mavlink_message_t msg;
1014 
1015  res.success = true;
1016  return true;
1017 }
1018 
1019 bool rosflightIO::calibrateRCTrimSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
1020 {
1021  mavlink_message_t msg;
1024  res.success = true;
1025  return true;
1026 }
1027 
1029 {
1031  {
1032  param_timer_.stop();
1033  ROS_INFO("Received all parameters");
1034  }
1035  else
1036  {
1038  ROS_ERROR("Received %d of %d parameters. Requesting missing parameters...",
1040  }
1041 }
1042 
1044 {
1045  request_version();
1046 }
1047 
1049 {
1050  send_heartbeat();
1051 }
1052 
1054 {
1055  mavlink_message_t msg;
1058 }
1060 {
1061  mavlink_message_t msg;
1062  mavlink_msg_heartbeat_pack(1, 50, &msg, 0, 0, 0, 0, 0);
1064 }
1065 
1066 void rosflightIO::check_error_code(uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name)
1067 {
1068  if ((current & code) != (previous & code))
1069  {
1070  if (current & code)
1071  ROS_ERROR("Autopilot ERROR: %s", name.c_str());
1072  else
1073  ROS_INFO("Autopilot RECOVERED ERROR: %s", name.c_str());
1074  }
1075 }
1076 
1077 bool rosflightIO::calibrateAirspeedSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
1078 {
1079  mavlink_message_t msg;
1082  res.success = true;
1083  return true;
1084 }
1085 
1086 bool rosflightIO::calibrateBaroSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
1087 {
1088  mavlink_message_t msg;
1091  res.success = true;
1092  return true;
1093 }
1094 
1095 bool rosflightIO::rebootSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
1096 {
1097  mavlink_message_t msg;
1100  res.success = true;
1101  return true;
1102 }
1103 
1104 bool rosflightIO::rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
1105 {
1106  mavlink_message_t msg;
1109  res.success = true;
1110  return true;
1111 }
1112 
1113 } // namespace rosflight_io
void versionTimerCallback(const ros::TimerEvent &e)
void handle_small_mag_msg(const mavlink_message_t &msg)
bool calibrateRCTrimSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void handle_battery_status_msg(const mavlink_message_t &msg)
ros::Publisher twist_stamped_pub_
Definition: rosflight_io.h:184
#define ROS_FATAL(...)
void handle_diff_pressure_msg(const mavlink_message_t &msg)
ros::Publisher attitude_pub_
Definition: rosflight_io.h:187
ros::Publisher unsaved_params_pub_
Definition: rosflight_io.h:172
static constexpr float HEARTBEAT_PERIOD
Definition: rosflight_io.h:103
void handle_heartbeat_msg(const mavlink_message_t &msg)
#define ROS_WARN_THROTTLE(rate,...)
ros::Publisher output_raw_pub_
Definition: rosflight_io.h:175
std::string get_major_minor_version(const std::string &version)
void publish(const boost::shared_ptr< M > &message) const
ros::ServiceServer calibrate_rc_srv_
Definition: rosflight_io.h:205
bool set_param_value(std::string name, double value)
f
virtual const char * what() const
Time & fromNSec(uint64_t t)
#define ROS_INFO_ONCE(...)
std::vector< double > values
OFFBOARD_CONTROL_IGNORE
Definition: rosflight.h:100
virtual void handle_mavlink_message(const mavlink_message_t &msg)
The handler function for mavlink messages to be implemented by derived classes.
ros::Subscriber extatt_sub_
Definition: rosflight_io.h:170
bool get_param_value(std::string name, double *value)
void handle_small_baro_msg(const mavlink_message_t &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
rosflight::ROSTimerProvider timer_provider_
Definition: rosflight_io.h:225
ros::Subscriber aux_command_sub_
Definition: rosflight_io.h:169
void handle_command_ack_msg(const mavlink_message_t &msg)
virtual void on_param_value_updated(std::string name, double value)
Called when an updated value is received for a parameter.
void handle_small_range_msg(const mavlink_message_t &msg)
void stop()
void check_error_code(uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name)
ros::Publisher baro_pub_
Definition: rosflight_io.h:179
virtual void on_params_saved_change(bool unsaved_changes)
Called when the status of whether there are unsaved parameters changes.
ros::ServiceServer reboot_srv_
Definition: rosflight_io.h:208
bool load_from_file(std::string filename)
bool paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
ros::Publisher nav_sat_fix_pub_
Definition: rosflight_io.h:183
void register_mavlink_listener(MavlinkListenerInterface *const listener)
Register a listener for mavlink messages.
bool save_to_file(std::string filename)
geometry_msgs::Quaternion attitude_quat_
Definition: rosflight_io.h:215
void handle_attitude_quaternion_msg(const mavlink_message_t &msg)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void handle_statustext_msg(const mavlink_message_t &msg)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void paramTimerCallback(const ros::TimerEvent &e)
#define ROS_WARN(...)
Describes an exception encountered while using the boost serial libraries.
bool calibrateBaroSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void open()
Opens the port and begins communication.
void handle_status_msg(const mavlink_message_t &msg)
ros::Publisher status_pub_
Definition: rosflight_io.h:189
void handle_rosflight_output_raw_msg(const mavlink_message_t &msg)
mavrosflight::MavlinkComm * mavlink_comm_
Definition: rosflight_io.h:220
void handle_named_value_int_msg(const mavlink_message_t &msg)
mavrosflight::MavROSflight< rosflight::ROSLogger > * mavrosflight_
Definition: rosflight_io.h:221
ros::Publisher gnss_full_pub_
Definition: rosflight_io.h:182
TimeManager< DerivedLogger > time
Definition: mavrosflight.h:80
static constexpr float PARAMETER_PERIOD
Definition: rosflight_io.h:105
ros::Publisher lidar_pub_
Definition: rosflight_io.h:191
ros::Publisher sonar_pub_
Definition: rosflight_io.h:180
ros::Publisher time_reference_pub_
Definition: rosflight_io.h:185
void handle_small_imu_msg(const mavlink_message_t &msg)
ROSLIB_DECL std::string command(const std::string &cmd)
void handle_named_command_struct_msg(const mavlink_message_t &msg)
rosflight::ROSLogger logger_
Definition: rosflight_io.h:223
#define ROS_INFO(...)
ros::Publisher imu_temp_pub_
Definition: rosflight_io.h:174
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool paramGetSrvCallback(rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res)
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
void heartbeatTimerCallback(const ros::TimerEvent &e)
bool rebootSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::ServiceServer param_set_srv_
Definition: rosflight_io.h:199
std::string getService() const
ROSFLIGHT_ERROR_CODE
Definition: rosflight.h:114
mavlink_rosflight_status_t prev_status_
Definition: rosflight_io.h:216
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::ServiceServer calibrate_baro_srv_
Definition: rosflight_io.h:206
void commandCallback(rosflight_msgs::Command::ConstPtr msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher version_pub_
Definition: rosflight_io.h:190
ros::Publisher error_pub_
Definition: rosflight_io.h:192
#define ROS_WARN_STREAM(args)
rosflight::ROSTimeInterface time_interface_
Definition: rosflight_io.h:224
TFSIMD_FORCE_INLINE const tfScalar & z() const
void handle_named_value_float_msg(const mavlink_message_t &msg)
bool paramSetSrvCallback(rosflight_msgs::ParamSet::Request &req, rosflight_msgs::ParamSet::Response &res)
bool paramWriteSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void externalAttitudeCallback(geometry_msgs::Quaternion::ConstPtr msg)
void auxCommandCallback(rosflight_msgs::AuxCommand::ConstPtr msg)
OFFBOARD_CONTROL_MODE
Definition: rosflight.h:85
ros::Publisher diff_pressure_pub_
Definition: rosflight_io.h:177
bool calibrateImuBiasSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void handle_hard_error_msg(const mavlink_message_t &msg)
std::chrono::nanoseconds fcu_time_to_system_time(std::chrono::nanoseconds fcu_time)
void handle_version_msg(const mavlink_message_t &msg)
void handle_rc_channels_raw_msg(const mavlink_message_t &msg)
void handle_rosflight_gnss_full_msg(const mavlink_message_t &msg)
ros::Publisher battery_status_pub_
Definition: rosflight_io.h:193
ros::ServiceServer imu_calibrate_bias_srv_
Definition: rosflight_io.h:203
ros::Publisher gnss_pub_
Definition: rosflight_io.h:181
void register_param_listener(ParamListenerInterface *listener)
static Time now()
T saturate(T value, T min, T max)
Definition: rosflight_io.h:161
ros::ServiceServer param_save_to_file_srv_
Definition: rosflight_io.h:201
ROSCPP_DECL void shutdown()
ros::Publisher euler_pub_
Definition: rosflight_io.h:188
ros::Subscriber command_sub_
Definition: rosflight_io.h:168
static constexpr float VERSION_PERIOD
Definition: rosflight_io.h:104
ros::ServiceServer calibrate_airspeed_srv_
Definition: rosflight_io.h:207
std::string getTopic() const
bool paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
std::map< std::string, ros::Publisher > named_value_int_pubs_
Definition: rosflight_io.h:194
void handle_rosflight_gnss_msg(const mavlink_message_t &msg)
ros::Publisher rc_raw_pub_
Definition: rosflight_io.h:176
bool rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer param_write_srv_
Definition: rosflight_io.h:200
ros::Time fcu_time_to_ros_time(std::chrono::nanoseconds fcu_time)
virtual void on_new_param_received(std::string name, double value)
Called when a parameter is received from the autopilot for the first time.
#define ROS_ERROR(...)
ros::ServiceServer reboot_bootloader_srv_
Definition: rosflight_io.h:209
ros::ServiceServer param_get_srv_
Definition: rosflight_io.h:198
bool calibrateAirspeedSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void send_message(const mavlink_message_t &msg)
Send a mavlink message.
ParamManager< DerivedLogger > param
Definition: mavrosflight.h:79
std::map< std::string, ros::Publisher > named_command_struct_pubs_
Definition: rosflight_io.h:196
std::map< std::string, ros::Publisher > named_value_float_pubs_
Definition: rosflight_io.h:195
ros::ServiceServer param_load_from_file_srv_
Definition: rosflight_io.h:202
#define ROS_DEBUG(...)
Logger implementation for ROS environments.
Definition: ros_logger.h:54


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:09:26