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)    49 #include <eigen3/Eigen/Core>    50 #include <eigen3/Eigen/Dense>    81   if (nh_private.
param<
bool>(
"udp", 
false))
    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);
    88     ROS_INFO(
"Connecting over UDP to \"%s:%d\", from \"%s:%d\"", remote_host.c_str(), remote_port, bind_host.c_str(),
    95     std::string port = nh_private.
param<std::string>(
"port", 
"/dev/ttyACM0");
    96     int baud_rate = nh_private.
param<
int>(
"baud_rate", 921600);
    98     ROS_INFO(
"Connecting to serial port \"%s\", at %d baud", port.c_str(), baud_rate);
   130   std_msgs::Bool unsaved_msg;
   131   unsaved_msg.data = 
false;
   223     ROS_DEBUG(
"rosflight_io: Got unhandled mavlink message ID %d", msg.msgid);
   230   ROS_DEBUG(
"Got parameter %s with value %g", name.c_str(), value);
   235   ROS_INFO(
"Parameter %s has new value %g", name.c_str(), value);
   241   msg.data = unsaved_changes;
   250     ROS_INFO(
"Onboard parameters have been saved");
   267     if (status_msg.
armed)
   279       ROS_INFO(
"Autopilot FAILSAFE RECOVERED");
   288       ROS_WARN(
"Returned to computer control");
   295       ROS_WARN(
"Computer control active");
   305                      "IMU not responding");
   308                      "Unhealthy estimator");
   310                      "Time going backwards");
   321     std::string mode_string;
   325       mode_string = 
"PASS_THROUGH";
   328       mode_string = 
"RATE";
   331       mode_string = 
"ANGLE";
   334       mode_string = 
"UNKNOWN";
   342   rosflight_msgs::Status out_status;
   344   out_status.armed = status_msg.
armed;
   345   out_status.failsafe = status_msg.
failsafe;
   347   out_status.offboard = status_msg.
offboard;
   349   out_status.error_code = status_msg.
error_code;
   350   out_status.num_errors = status_msg.
num_errors;
   410   rosflight_msgs::Attitude attitude_msg;
   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;
   421   geometry_msgs::Vector3Stamped euler_msg;
   422   euler_msg.header.stamp = attitude_msg.header.stamp;
   447   sensor_msgs::Imu imu_msg;
   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;
   458   sensor_msgs::Temperature temp_msg;
   459   temp_msg.header.stamp = imu_msg.header.stamp;
   481   rosflight_msgs::OutputRaw out_msg;
   483   for (
int i = 0; i < 14; i++)
   485     out_msg.values[i] = servo.
values[i];
   500   rosflight_msgs::RCRaw out_msg;
   524   rosflight_msgs::Airspeed airspeed_msg;
   526   airspeed_msg.velocity = diff.
velocity;
   552   std::string name(c_name);
   560   std_msgs::Int32 out_msg;
   561   out_msg.data = val.
value;
   575   std::string name(c_name);
   583   std_msgs::Float32 out_msg;
   584   out_msg.data = val.
value;
   598   std::string name(c_name);
   606   rosflight_msgs::Command command_msg;
   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;
   627   rosflight_msgs::Barometer baro_msg;
   652   sensor_msgs::MagneticField mag_msg;
   656   mag_msg.magnetic_field.x = mag.
xmag;
   657   mag_msg.magnetic_field.y = mag.
ymag;
   658   mag_msg.magnetic_field.z = mag.
zmag;
   672   sensor_msgs::Range alt_msg;
   676   alt_msg.range = range.
range;
   681     alt_msg.radiation_type = sensor_msgs::Range::ULTRASOUND;
   682     alt_msg.field_of_view = 1.0472; 
   691     alt_msg.radiation_type = sensor_msgs::Range::INFRARED;
   692     alt_msg.field_of_view = .0349066; 
   714   size_t start_index = 0;
   715   if (version[0] == 
'v' || version[0] == 
'V') 
   717   size_t dot_index = version.find(
'.');         
   718   dot_index = version.find(
'.', dot_index + 1); 
   719   return version.substr(start_index, dot_index - start_index);
   729   std_msgs::String version_msg;
   730   version_msg.data = version.
version;
   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;
   740   const std::string firmware_version(version.
version);
   742   if (rosflight_major_minor_version == firmware_major_minor_version)
   744     ROS_INFO(
"ROSflight/firmware version: %s", firmware_major_minor_version.c_str());
   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());
   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);
   763   ROS_ERROR(
"Hard fault detected, with error code %u. The flight controller has rebooted.", error.
error_code);
   767     ROS_ERROR(
"The firmware has rearmed itself.");
   770   rosflight_msgs::Error error_msg;
   771   error_msg.error_message = 
"A firmware error has caused the flight controller to reboot.";
   774   error_msg.rearm = error.
doRearm;
   775   error_msg.pc = error.
pc;
   786   rosflight_msgs::BatteryStatus battery_status_message;
   800   rosflight_msgs::GNSS gnss_msg;
   801   gnss_msg.header.stamp = stamp;
   802   gnss_msg.header.frame_id = 
"ECEF";
   805   gnss_msg.position[0] = .01 * gnss.
ecef_x; 
   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; 
   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;
   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;    
   824   navsat_fix.longitude = 1e-7 * gnss.
lon;   
   825   navsat_fix.altitude = .001 * gnss.
height; 
   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;
   836     navsat_status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
   839     navsat_status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
   842     navsat_status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
   845   navsat_status.service = 1; 
   846   navsat_fix.status = navsat_status;
   854   geometry_msgs::TwistStamped twist_stamped;
   855   twist_stamped.header.stamp = stamp;
   857   twist_stamped.twist.angular.x = 0;
   858   twist_stamped.twist.angular.y = 0;
   859   twist_stamped.twist.angular.z = 0;
   861   twist_stamped.twist.linear.x = .001 * gnss.
vel_n; 
   862   twist_stamped.twist.linear.y = .001 * gnss.
vel_e;
   863   twist_stamped.twist.linear.z = .001 * gnss.
vel_d;
   869   sensor_msgs::TimeReference time_ref;
   870   time_ref.header.stamp = stamp;
   871   time_ref.source = 
"GNSS";
   885   rosflight_msgs::GNSSFull msg_out;
   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;
   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;
   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;
   910   msg_out.s_acc = full.
s_acc;
   912   msg_out.p_dop = full.
p_dop;
   946   mavlink_message_t mavlink_msg;
   955   for (
int i = 0; i < 14; i++)
   957     types[i] = msg->type_array[i];
   958     values[i] = msg->values[i];
   960   mavlink_message_t mavlink_msg;
   967   mavlink_message_t mavlink_msg;
   989     res.message = 
"Request rejected: write already in progress";
   996                                           rosflight_msgs::ParamFile::Response &res)
  1003                                             rosflight_msgs::ParamFile::Response &res)
  1011   mavlink_message_t msg;
  1021   mavlink_message_t msg;
  1033     ROS_INFO(
"Received all parameters");
  1038     ROS_ERROR(
"Received %d of %d parameters. Requesting missing parameters...",
  1055   mavlink_message_t msg;
  1061   mavlink_message_t msg;
  1068   if ((current & code) != (previous & code))
  1071       ROS_ERROR(
"Autopilot ERROR: %s", name.c_str());
  1073       ROS_INFO(
"Autopilot RECOVERED ERROR: %s", name.c_str());
  1079   mavlink_message_t msg;
  1088   mavlink_message_t msg;
  1097   mavlink_message_t msg;
  1106   mavlink_message_t msg;
 
void versionTimerCallback(const ros::TimerEvent &e)
static uint16_t mavlink_msg_offboard_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t mode, uint8_t ignore, float x, float y, float z, float F)
Pack a offboard_control message. 
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION
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)
static void mavlink_msg_small_range_decode(const mavlink_message_t *msg, mavlink_small_range_t *small_range)
Decode a small_range message into a struct. 
ros::Publisher twist_stamped_pub_
#define MAVLINK_MSG_ID_SMALL_IMU
void handle_diff_pressure_msg(const mavlink_message_t &msg)
ros::Publisher attitude_pub_
ros::Publisher unsaved_params_pub_
static constexpr float HEARTBEAT_PERIOD
static void mavlink_msg_small_baro_decode(const mavlink_message_t *msg, mavlink_small_baro_t *small_baro)
Decode a small_baro message into a struct. 
void handle_heartbeat_msg(const mavlink_message_t &msg)
static uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
Pack a heartbeat message. 
#define ROS_WARN_THROTTLE(rate,...)
ros::Publisher output_raw_pub_
std::string get_major_minor_version(const std::string &version)
void publish(const boost::shared_ptr< M > &message) const 
#define MAVLINK_MSG_ID_ROSFLIGHT_HARD_ERROR
#define MAVLINK_MSG_ID_HEARTBEAT
ros::ServiceServer calibrate_rc_srv_
static void mavlink_msg_rosflight_cmd_ack_decode(const mavlink_message_t *msg, mavlink_rosflight_cmd_ack_t *rosflight_cmd_ack)
Decode a rosflight_cmd_ack message into a struct. 
bool set_param_value(std::string name, double value)
virtual const char * what() const 
Time & fromNSec(uint64_t t)
#define ROS_INFO_ONCE(...)
std::vector< double > values
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_
static void mavlink_msg_rosflight_hard_error_decode(const mavlink_message_t *msg, mavlink_rosflight_hard_error_t *rosflight_hard_error)
Decode a rosflight_hard_error message into a struct. 
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 
#define MAVLINK_MSG_ID_TIMESYNC
rosflight::ROSTimerProvider timer_provider_
#define MAVLINK_MSG_ID_SMALL_BARO
ros::Subscriber aux_command_sub_
void handle_command_ack_msg(const mavlink_message_t &msg)
#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_FULL
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)
static void mavlink_msg_small_imu_decode(const mavlink_message_t *msg, mavlink_small_imu_t *small_imu)
Decode a small_imu message into a struct. 
void check_error_code(uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name)
static void mavlink_msg_small_mag_decode(const mavlink_message_t *msg, mavlink_small_mag_t *small_mag)
Decode a small_mag message into a struct. 
virtual void on_params_saved_change(bool unsaved_changes)
Called when the status of whether there are unsaved parameters changes. 
ros::ServiceServer reboot_srv_
bool load_from_file(std::string filename)
#define MAVLINK_MSG_ID_RC_CHANNELS
static void mavlink_msg_diff_pressure_decode(const mavlink_message_t *msg, mavlink_diff_pressure_t *diff_pressure)
Decode a diff_pressure message into a struct. 
bool paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
ros::Publisher nav_sat_fix_pub_
#define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT
void register_mavlink_listener(MavlinkListenerInterface *const listener)
Register a listener for mavlink messages. 
bool save_to_file(std::string filename)
static uint16_t mavlink_msg_external_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, float qw, float qx, float qy, float qz)
Pack a external_attitude message. 
static void mavlink_msg_named_value_int_decode(const mavlink_message_t *msg, mavlink_named_value_int_t *named_value_int)
Decode a named_value_int message into a struct. 
geometry_msgs::Quaternion attitude_quat_
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)
Describes an exception encountered while using the boost serial libraries. 
#define MAVLINK_MSG_ID_DIFF_PRESSURE
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_
static void mavlink_msg_rosflight_version_decode(const mavlink_message_t *msg, mavlink_rosflight_version_t *rosflight_version)
Decode a rosflight_version message into a struct. 
ros::Timer version_timer_
void handle_rosflight_output_raw_msg(const mavlink_message_t &msg)
mavrosflight::MavlinkComm * mavlink_comm_
static void mavlink_msg_rosflight_battery_status_decode(const mavlink_message_t *msg, mavlink_rosflight_battery_status_t *rosflight_battery_status)
Decode a rosflight_battery_status message into a struct. 
void handle_named_value_int_msg(const mavlink_message_t &msg)
static void mavlink_msg_rosflight_status_decode(const mavlink_message_t *msg, mavlink_rosflight_status_t *rosflight_status)
Decode a rosflight_status message into a struct. 
mavrosflight::MavROSflight< rosflight::ROSLogger > * mavrosflight_
ros::Publisher gnss_full_pub_
TimeManager< DerivedLogger > time
static constexpr float PARAMETER_PERIOD
#define MAVLINK_MSG_ID_SMALL_RANGE
ros::Publisher lidar_pub_
ros::Publisher sonar_pub_
ros::Publisher time_reference_pub_
#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN
void handle_small_imu_msg(const mavlink_message_t &msg)
ROSLIB_DECL std::string command(const std::string &cmd)
#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW
static void mavlink_msg_rosflight_gnss_decode(const mavlink_message_t *msg, mavlink_rosflight_gnss_t *rosflight_gnss)
Decode a rosflight_gnss message into a struct. 
static void mavlink_msg_rosflight_gnss_full_decode(const mavlink_message_t *msg, mavlink_rosflight_gnss_full_t *rosflight_gnss_full)
Decode a rosflight_gnss_full message into a struct. 
void handle_named_command_struct_msg(const mavlink_message_t &msg)
int get_params_received()
rosflight::ROSLogger logger_
ros::Publisher imu_temp_pub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
bool paramGetSrvCallback(rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res)
static void mavlink_msg_named_value_float_decode(const mavlink_message_t *msg, mavlink_named_value_float_t *named_value_float)
Decode a named_value_float message into a struct. 
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_
static uint16_t mavlink_msg_rosflight_cmd_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t command)
Pack a rosflight_cmd message. 
std::string getService() const 
ros::Timer heartbeat_timer_
#define MAVLINK_MSG_ID_ROSFLIGHT_BATTERY_STATUS
mavlink_rosflight_status_t prev_status_
TFSIMD_FORCE_INLINE const tfScalar & x() const 
ros::ServiceServer calibrate_baro_srv_
void commandCallback(rosflight_msgs::Command::ConstPtr msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define MAVLINK_MSG_ID_PARAM_VALUE
ros::Publisher version_pub_
static void mavlink_msg_named_command_struct_decode(const mavlink_message_t *msg, mavlink_named_command_struct_t *named_command_struct)
Decode a named_command_struct message into a struct. 
ros::Publisher error_pub_
#define ROS_WARN_STREAM(args)
rosflight::ROSTimeInterface time_interface_
static void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t *msg, mavlink_attitude_quaternion_t *attitude_quaternion)
Decode a attitude_quaternion message into a struct. 
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)
#define MAVLINK_MSG_ID_STATUSTEXT
void externalAttitudeCallback(geometry_msgs::Quaternion::ConstPtr msg)
#define MAVLINK_MSG_ID_ROSFLIGHT_STATUS
void auxCommandCallback(rosflight_msgs::AuxCommand::ConstPtr msg)
static uint16_t mavlink_msg_rosflight_aux_cmd_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const uint8_t *type_array, const float *aux_cmd_array)
Pack a rosflight_aux_cmd message. 
ros::Publisher diff_pressure_pub_
bool calibrateImuBiasSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void handle_hard_error_msg(const mavlink_message_t &msg)
#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN
#define MAVLINK_MSG_ID_SMALL_MAG
std::chrono::nanoseconds fcu_time_to_system_time(std::chrono::nanoseconds fcu_time)
void handle_version_msg(const mavlink_message_t &msg)
static void mavlink_msg_statustext_decode(const mavlink_message_t *msg, mavlink_statustext_t *statustext)
Decode a statustext message into a struct. 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT
void handle_rc_channels_raw_msg(const mavlink_message_t &msg)
#define MAVLINK_MSG_ID_ROSFLIGHT_CMD_ACK
void handle_rosflight_gnss_full_msg(const mavlink_message_t &msg)
ros::Publisher battery_status_pub_
ros::ServiceServer imu_calibrate_bias_srv_
static void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t *msg, mavlink_rc_channels_raw_t *rc_channels_raw)
Decode a rc_channels_raw message into a struct. 
void register_param_listener(ParamListenerInterface *listener)
T saturate(T value, T min, T max)
ros::ServiceServer param_save_to_file_srv_
ROSCPP_DECL void shutdown()
ros::Publisher euler_pub_
ros::Subscriber command_sub_
static constexpr float VERSION_PERIOD
#define MAVLINK_MSG_ID_ROSFLIGHT_VERSION
static void mavlink_msg_rosflight_output_raw_decode(const mavlink_message_t *msg, mavlink_rosflight_output_raw_t *rosflight_output_raw)
Decode a rosflight_output_raw message into a struct. 
ros::ServiceServer calibrate_airspeed_srv_
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_
void handle_rosflight_gnss_msg(const mavlink_message_t &msg)
uint64_t rosflight_timestamp
ros::Publisher rc_raw_pub_
bool rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer param_write_srv_
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. 
ros::ServiceServer reboot_bootloader_srv_
ros::ServiceServer param_get_srv_
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
std::map< std::string, ros::Publisher > named_command_struct_pubs_
#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS
std::map< std::string, ros::Publisher > named_value_float_pubs_
ros::ServiceServer param_load_from_file_srv_
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT
Logger implementation for ROS environments.