GithubHelp home page GithubHelp logo

ethz-asl / mav_control_rw Goto Github PK

View Code? Open in Web Editor NEW
339.0 41.0 156.0 2.29 MB

Control strategies for rotary wing Micro Aerial Vehicles using ROS

License: Apache License 2.0

CMake 0.26% C++ 21.33% Python 0.13% C 78.11% Makefile 0.05% MATLAB 0.12%
ros trajectory-tracking control uav

mav_control_rw's Introduction

mav_control_rw Build Status

Control strategies for rotary wing Micro Aerial Vehicles (MAVs) using ROS

Overview

This repository contains controllers for rotary wing MAVs. Currently we support the following controllers:

  • mav_linear_mpc : Linear MPC for MAV trajectory tracking
  • mav_nonlinear_mpc : Nonlinear MPC for MAV trajectory tracking
  • PID_attitude_control : low level PID attitude controller

Moreover, an external disturbance observer based on Kalman Filter is implemented to achieve offset-free tracking.

If you use any of these controllers within your research, please cite one of the following references

@incollection{kamelmpc2016,
                author      = "Mina Kamel and Thomas Stastny and Kostas Alexis and Roland Siegwart",
                title       = "Model Predictive Control for Trajectory Tracking of Unmanned Aerial Vehicles Using Robot Operating System",
                editor      = "Anis Koubaa",
                booktitle   = "Robot Operating System (ROS) The Complete Reference, Volume 2",
                publisher   = "Springer",
                year = “2017”,
}
@ARTICLE{2016arXiv161109240K,
          author = {{Kamel}, M. and {Burri}, M. and {Siegwart}, R.},
          title = "{Linear vs Nonlinear MPC for Trajectory Tracking Applied to Rotary Wing Micro Aerial Vehicles}",
          journal = {ArXiv e-prints},
          archivePrefix = "arXiv",
          eprint = {1611.09240},
          primaryClass = "cs.RO",
          keywords = {Computer Science - Robotics},
          year = 2016,
          month = nov
}

Installation instructions

To run the controller with RotorS simulator (https://github.com/ethz-asl/rotors_simulator), follow these instructions:

  • Install and initialize ROS indigo desktop full, additional ROS packages, catkin-tools:
  $ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -sc` main" > /etc/apt/sources.list.d/ros-latest.list'
  $ wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
  $ sudo apt-get update
  $ sudo apt-get install ros-indigo-desktop-full ros-indigo-joy ros-indigo-octomap-ros python-wstool python-catkin-tools
  $ sudo rosdep init
  $ rosdep update
  $ source /opt/ros/indigo/setup.bash
  • Initialize catkin workspace:
  $ mkdir -p ~/catkin_ws/src
  $ cd ~/catkin_ws
  $ catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
  $ catkin init  # initialize your catkin workspace
  • Get the controllers and dependencies
  $ sudo apt-get install liblapacke-dev
  $ git clone https://github.com/catkin/catkin_simple.git
  $ git clone https://github.com/ethz-asl/rotors_simulator.git
  $ git clone https://github.com/ethz-asl/mav_comm.git
  $ git clone https://github.com/ethz-asl/eigen_catkin.git

  $ git clone https://github.com/ethz-asl/mav_control_rw.git
  • Build the workspace
  $ catkin build
  • Run the simulator and the linear MPC. In seperate terminals run the following commands
  $ roslaunch rotors_gazebo mav.launch mav_name:=firefly
  $ roslaunch mav_linear_mpc mav_linear_mpc_sim.launch mav_name:=firefly

You can use rqt to publish commands to the controller.

To run the controller with the multi sensor fusion (MSF) framewok (https://github.com/ethz-asl/ethzasl_msf):

  • Get msf
  $ git clone https://github.com/ethz-asl/ethzasl_msf.git
  • Run the simulator, the linear MPC and MSF, in seperate terminals run the following commands
  $ roslaunch rotors_gazebo mav.launch mav_name:=firefly
  $ roslaunch mav_linear_mpc mav_linear_mpc_sim_msf.launch mav_name:=firefly

Don't forget to initialize MSF.

Supported autopilots

Asctec Research Platforms

This control will work as is with the ros interface to the now discontinued Asctec research platforms (Hummingbird, Pelican, Firefly and Neo).

Pixhawk

This controller requires some small modifications to the PX4 firmware to allow yaw rate inputs. A modified version of the firmware can be found here. The firmware is interfaced with through a modified mavros node.

DJI

The controller can interface with DJI platforms through our mav_dji_ros_interface

Published and subscribed topics

The linear and nonlinear MPC controllers publish and subscribe to the following topics:

  • Published topics:

    • command/roll_pitch_yawrate_thrust of type mav_msgs/RollPitchYawrateThrust. This is the command to the low level controller. Angles are in rad and thrust is in N.
    • command/current_reference of type trajectory_msgs/MultiDOFJointTrajectory. This is the current reference.
    • state_machine/state_info of type std_msgs/String. This is the current state of the state machine of mav_control_interface.
    • predicted_state of type visualization_msgs/Marker. This is the predicted vehicle positions that can be used for visualization in rviz.
    • reference_trajectory of type visualization_msgs/Marker. This is the reference trajectory that can be used for visualization in rviz.
    • KF_observer/observer_state of type mav_disturbance_observer/ObserverState. This is the disturbance observer state used for debugging purposes. It includes estimated external forces and torques.
  • Subscribed topics:

    • command/pose of type geometry_msgs/PoseStamped. This is a reference set point.
    • command/trajectory of type trajectory_msgs/MultiDOFJointTrajectory. This is a desired trajectory reference that includes desired velocities and accelerations.
    • rc of type sensor_msgs/Joy. This is the remote control commands for teleoperation purposes. It also serves to abort mission anytime.
    • odometry of type nav_msgs/Odometry. This is the current state of the vehicle. The odometry msg includes pose and twist information.

The PID attitude controller publishes and subscribes to the following topics:

  • Published topics:

    • command/motor_speed of type mav_msgs/Actuators. This is the commanded motor speed.
  • Subscribed topics:

    • command/roll_pitch_yawrate_thrust of type mav_msgs/RollPitchYawrateThrust.
    • odometry of type nav_msgs/Odometry.

Parameters

A summary of the linear and nonlinear MPC parameters:

Parameter Description
use_rc_teleop enable RC teleoperation. Set to false in case of simulation.
reference_frame the name of the reference frame.
verbose controller prints on screen debugging information and computation time
mass vehicle mass
roll_time_constant time constant of roll first order model
pitch_time_constant time constant of pitch first order model
roll_gain gain of roll first order model
pitch_gain gain of pitch first order model
drag_coefficients drag on x,y,z axes
q_x, q_y, q_z* penalty on position error
q_vx, q_vy, q_vz* penalty on velocity error
q_roll, q_pitch* penalty on attitude state
r_roll, r_pitch, r_thtust* penalty on control input
r_droll, r_dpitch, r_dthtust* penalty on delta control input (only Linear MPC)
roll_max, pitch_max, yaw_rate_max* limits of control input
thrust_min, thrust_max* limit on thrust control input in m/s^2
K_yaw* yaw P loop gain
Ki_xy, Ki_z* integrator gains on xy and z axes respectively
position_error_integration_limit limit of position error integration
antiwindup_ball if the error is larger than this ball, no integral action is applied
enable_offset_free* use estimated disturbances to achieve offset free tracking
enable_integrator* use error integration to achieve offset free tracking
sampling_time the controller sampling time (must be equal to the rate of odometry message
prediction_sampling_time the prediction sampling time inside the controller

* Through dynamic reconfigure, it is possible to change these parameters.


A summary of the PID attitude parameters:

Parameter Description
inertia vehicle inertia 3x3 matrix
allocation_matrix control allocation matrix depending on the configuration of the rotors
n_rotors number of rotors
rotor_force_constant force constant of the rotor in N/rad^2 such that F_i =rotor_force_constant*rotor_velocity^2
rotor_moment_constant rotor moment constant such that M = rotor_moment_constant*F_i
arm_length distance between rotor and vehicle center
roll_gain, pitch_gain* error proportional term
p_gain, q_gain, r_gain* derivative gain
roll_int_gain, pitch_int_gain* integrator gains
max_integrator_error saturation on the integrator

* Through dynamic reconfigure, it is possible to change these parameters.


References

[1] Model Predictive Control for Trajectory Tracking of Unmanned Aerial Vehicles Using Robot Operating System. Mina Kamel, Thomas Stastny, Kostas Alexis and Roland Siegwart. Robot Operating System (ROS) The Complete Reference Volume 2. Springer 2017 (to appear)

[2] Linear vs Nonlinear MPC for Trajectory Tracking Applied to Rotary Wing Micro Aerial Vehicles. Mina Kamel, Michael Burri and Roland Siegwart. arXiv:1611.09240


Contact

Mina Kamel fmina(at)ethz.ch

mav_control_rw's People

Contributors

fmina avatar helenol avatar oggepogge avatar zacharytaylor avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

mav_control_rw's Issues

No lift-off when the mav_nonlinear_mpc controller is used

Hi,

I am on ROS Kinetic, and am trying to use the rotors-simulation package for some of my experiments. Initially, I am using the mav_trajectory_generation package to generate a trajectory through the desired points, and publishing this trajectory_msgs/MultiDOFJointTrajectory message on a topic. Then, I am making use of the mav_control_rw package, and specifically the non linear controller provided in that package to make my hummingbird UAV go through the desired points. But when I run the mav_nonlinear_mpc_sim.launch file, my UAV does not take off, and the rotors keep rotating. When I echo the /hummingbird/command/motor_speed topic, I notice that the motor speeds are around 400, which dosent seem to be sufficient to fly the UAV.

I am not able to resolve this issue. Any help from you guys will be greatly appreciated.

Thanks

New quadrotor Parrot Bebop simulation

Hi there,

I am trying to use the package to control a Parrot Bebop together with rotors_simulator. The newly added quadrotor flies well using the lee_position_controller in rotors_simulator, but crashed quickly when trying to use either linear or nonlinear MPC. I added a configuration file similar to PID_attitude_hummingbird.yaml with inertia tensor, arm length modifications, and I guess the immediate crash may because of the allocation_matrix. I wonder could you help me with this? Thank you so much for any advice.

Regards,
Jie

speed up building time

is there any modification one can do to this awesome package to speed up the building time?
on a i7 10th gen is taking more than 15 min, which is way too much time
Thank you in advance

Real hardware implementation

Hi,

How should I proceed to implement this on real hardware with the hacked version of px4 firmware and hacked mavros?

  • Do you have a node that publish on a mavros topic from command/roll_pitch_yawrate_thrust ?
  • And on which mavros topic should I publish for the hacked version?

Thanks a lot.

Tuning recommendations

Hi,

In the data processing section of Zac's instructions on controller tuning the example output shows some parameters like "drag coefficients" and "yaw_gain" which don't show up when I run the mav_sysid.m script. Do you have any recommendations on tuning these parameters that aren't output by the sysid script?

Thank you

PELICAN IS NOT FOUND

When I pass pelican to the mav_name:= parameter, while launching the controller, it can not find the file. Anyone faced this issue?

Thank you.

Assertion failed in in mav_linear_mpc

Hi,

I was trying to run the simulation with linear MPC as described in wiki. However, I faced with the assertion failed. Below my log:

[ INFO] [1486490091.169850171]: start initializing mav_disturbance_observer:KF
[ INFO] [1486490091.171269822]: mav_disturbance_observer:KF dynamic config is called successfully
[ INFO] [1486490091.186612678]: KF parameters loaded successfully
[ INFO] [1486490091.187209009]: state_covariance_: 
0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1
[ INFO] [1486490091.187399030]: Kalman Filter Initialized!
[ INFO] [1486490091.212209782]: Linear MPC: Steady State calculation is initialized correctly
[ INFO] [1486490091.212391470]: A: 
         1          0          0    0.09995          0          0          0  0.0431908
         0          1          0          0    0.09995          0 -0.0430852          0
         0          0          1          0          0        0.1          0          0
         0          0          0      0.999          0          0          0   0.810794
         0          0          0          0      0.999          0  -0.807829          0
         0          0          0          0          0          1          0          0
         0          0          0          0          0          0    0.67032          0
         0          0          0          0          0          0          0   0.675598
[ INFO] [1486490091.212478409]: B: 
         0 0.00516734          0
 -0.005261          0          0
         0          0    0.00495
         0   0.151006          0
 -0.153652          0          0
         0          0        0.1
  0.297306          0          0
         0   0.292535          0
[ INFO] [1486490091.212546850]: B_d: 
0.00494836          0          0
         0 0.00494836          0
         0          0    0.00495
 0.0999505          0          0
         0  0.0999505          0
         0          0        0.1
         0          0          0
         0          0          0
[ INFO] [1486490091.212668776]: Linear MPC: initialized correctly
[ INFO] [1486490091.368251690, 16.800000000]: Linear MPC: Tuning parameters updated...
[ INFO] [1486490091.368404294, 16.800000000]: diag(Q) = 
40 40 60 20 20 25 20 20
[ INFO] [1486490091.368559821, 16.800000000]: diag(R) = 
35 35  2
[ INFO] [1486490091.368584806, 16.800000000]: diag(R_delta) = 
    0.3    0.3 0.0025
[ INFO] [1486490091.368750368, 16.800000000]: Q_final = 
 428.621        0        0  108.103        0        0        0  108.491
       0  427.748        0        0  107.214        0 -106.405        0
       0        0  563.584        0        0   111.51        0        0
 108.103        0        0  109.174        0        0        0  108.329
       0  107.214        0        0  108.248        0 -105.983        0
       0        0   111.51        0        0  111.486        0        0
       0 -106.405        0        0 -105.983        0  176.989        0
 108.491        0        0  108.329        0        0        0  182.576
[ INFO] [1486490091.402386001, 16.840000000]: Created control interface for controller linear_model_predictive_controller and RC ACI rc interface
mav_linear_mpc_node: /usr/include/boost/msm/front/state_machine_def.hpp:203: void boost::msm::front::state_machine_def<Derived, BaseState>::no_transition(const Event&, FSM&, int) [with FSM = boost::msm::back::state_machine<mav_control_interface::state_machine::StateMachineDefinition, boost::msm::back::mpl_graph_fsm_check>; Event = mav_control_interface::state_machine::OdometryWatchdog; Derived = mav_control_interface::state_machine::StateMachineDefinition; BaseState = boost::msm::front::default_base_state]: Assertion `false' failed.
[firefly/mav_linear_mpc-1] process has died [pid 31591, exit code -6, cmd /home/alex/catkin_ws/devel/lib/mav_linear_mpc/mav_linear_mpc_node odometry:=msf_core/odometry __name:=mav_linear_mpc __log:=/home/alex/.ros/log/60b83636-ed5e-11e6-ac08-10c37bc7c393/firefly-mav_linear_mpc-1.log].
log file: /home/alex/.ros/log/60b83636-ed5e-11e6-ac08-10c37bc7c393/firefly-mav_linear_mpc-1*.log
[firefly/mav_linear_mpc-1] restarting process

How can I solve it? What is a reason such fail?

Alex

Question About Trajectory Command

Hello, I am struggling on getting the MPC to work in order UAV to follow a trajectory command. The UAV will follow a command under the /command/pose topic perfectly. However, the UAV flies all over the place when I feed the MPC a trajectory command (the nonlinear MPC cannot solve when it is a trajectory command).

Right now, I am repeatedly (at the same frequency as the odom topic) sending a /trajectory/command topic to the MPC. The topic has the current reference sent in point 1, all the other future points include information on estimated future references. However, the MPC is giving nonsensical roll, pitch, yaw rate commands when considering these future references.

Is this how the trajectory command is supposed to be sent? Does anyone have an example?

the modified mavros node build

when i buid the modified mavros node for this project, there is a problem below, i think the modified mavros node is suitable for this project rather than the origial mavros, could you please give me some advise? thanks a lot!
2021-03-01 21-37-12 的屏幕截图

Example of commands to the controller

Hi,

Thank you for good work.

I have successfully compiled and run described launch files in the readme. However, I stuck on the following:

You can use rqt to publish commands to the controller.

Are there any examples what should I publish into topics to run the controller?

I guess that I need to publish into /firefly/command/current_reference. Am I right? If so how exactly should I write a trajectory into the message publisher?

Best Regards,
Alex

Question about reference state

Hi,

I saw that the topic /hummingbird/command/current_reference outputs a different reference than the one that I provide through /hummingbird/command/trajectory, if I assemble all the refs in a trajectory. Do you know why?

Cannot Seem to get all packages to catkin build

virtualpullu@virtual-PulluBox:~/catkin_ws/src$ catkin build

Profile: default
Extending: [explicit] /opt/ros/melodic
Workspace: /home/virtualpullu/catkin_ws

Build Space: [exists] /home/virtualpullu/catkin_ws/build
Devel Space: [exists] /home/virtualpullu/catkin_ws/devel
Install Space: [unused] /home/virtualpullu/catkin_ws/install
Log Space: [missing] /home/virtualpullu/catkin_ws/logs
Source Space: [exists] /home/virtualpullu/catkin_ws/src
DESTDIR: [unused] None

Devel Space Layout: merged
Install Space Layout: None

Additional CMake Args: -DCMAKE_BUILD_TYPE=Release
Additional Make Args: None
Additional catkin Make Args: None
Internal Make Job Server: True
Cache Job Environments: False

Whitelisted Packages: None
Blacklisted Packages: None

Workspace configuration appears valid.

NOTE: Forcing CMake to run for each package.

[build] Found '35' packages in 0.0 seconds.
[build] Updating package table.
Starting >>> catkin_simple
Finished <<< catkin_simple [ 2.4 seconds ]
Starting >>> mav_msgs


Errors << mav_msgs:cmake /home/virtualpullu/catkin_ws/logs/mav_msgs/build.cmake.000.log
CMake Error at /opt/ros/melodic/share/catkin/cmake/catkinConfig.cmake:83 (find_package):
Could not find a package configuration file provided by "trajectory_msgs"
with any of the following names:

trajectory_msgsConfig.cmake
trajectory_msgs-config.cmake

Add the installation prefix of "trajectory_msgs" to CMAKE_PREFIX_PATH or
set "trajectory_msgs_DIR" to a directory containing one of the above files.
If "trajectory_msgs" provides a separate development package or SDK, be
sure it has been installed.
Call Stack (most recent call first):
CMakeLists.txt:4 (find_package)

cd /home/virtualpullu/catkin_ws/build/mav_msgs; catkin build --get-env mav_msgs | catkin env -si /usr/bin/cmake /home/virtualpullu/catkin_ws/src/mav_comm/mav_msgs --no-warn-unused-cli -DCATKIN_DEVEL_PREFIX=/home/virtualpullu/catkin_ws/devel -DCMAKE_INSTALL_PREFIX=/home/virtualpullu/catkin_ws/install -DCMAKE_BUILD_TYPE=Release; cd -
....................................................................................................
Failed << mav_msgs:cmake [ Exited with code 1 ]
Failed <<< mav_msgs [ 2.3 seconds ]
Abandoned <<< mav_state_machine_msgs [ Unrelated job failed ]
Abandoned <<< mav_system_msgs [ Unrelated job failed ]
Abandoned <<< rotors_comm [ Unrelated job failed ]
Abandoned <<< rotors_description [ Unrelated job failed ]
Abandoned <<< rotors_evaluation [ Unrelated job failed ]
Abandoned <<< rqt_rotors [ Unrelated job failed ]
Abandoned <<< eigen_catkin [ Unrelated job failed ]
Abandoned <<< flightlib [ Unrelated job failed ]
Abandoned <<< flightrender [ Unrelated job failed ]
Abandoned <<< quad_launch_files [ Unrelated job failed ]
Abandoned <<< quadrotor_msgs [ Unrelated job failed ]
Abandoned <<< rpg_single_board_io [ Unrelated job failed ]
Abandoned <<< mav_planning_msgs [ Unrelated job failed ]
Abandoned <<< quadrotor_common [ Unrelated job failed ]
Abandoned <<< polynomial_trajectories [ Unrelated job failed ]
Abandoned <<< position_controller [ Unrelated job failed ]
Abandoned <<< rotors_control [ Unrelated job failed ]
Abandoned <<< rotors_gazebo_plugins [ Unrelated job failed ]
Abandoned <<< rotors_gazebo [ Unrelated job failed ]
Abandoned <<< rotors_hil_interface [ Unrelated job failed ]
Abandoned <<< rotors_joy_interface [ Unrelated job failed ]
Abandoned <<< rpg_rotors_interface [ Unrelated job failed ]
Abandoned <<< rqt_quad_gui [ Unrelated job failed ]
Abandoned <<< sbus_bridge [ Unrelated job failed ]
Abandoned <<< manual_flight_assistant [ Unrelated job failed ]
Abandoned <<< state_predictor [ Unrelated job failed ]
Abandoned <<< trajectory_generation_helper [ Unrelated job failed ]
Abandoned <<< autopilot [ Unrelated job failed ]
Abandoned <<< flightros [ Unrelated job failed ]
Abandoned <<< rpg_quadrotor_integration_test [ Unrelated job failed ]
Abandoned <<< vbat_thrust_calibration [ Unrelated job failed ]
[build] Summary: 1 of 33 packages succeeded.
[build] Ignored: 2 packages were skipped or are blacklisted.
[build] Warnings: None.
[build] Abandoned: 31 packages were abandoned.
[build] Failed: 1 packages failed.
[build] Runtime: 5.0 seconds total.
[build] Note: Workspace packages have changed, please re-source setup files to use them.

Typos in steady_state_calculation.cpp

Hi,

I faced with typos in steady_state_calculation.cpp here

I am sure these lines should be:

  assert(steadystate_state);
  assert(steadystate_input);

or you need to fix these names into method header.

Catkin build error on rotors_gazebo_plugins

Hi team,

I tried to follow the install instruction and ended up with this error. I have tried to ignore the package, but then I was unable to control the drone using ros publish command to command/pose topic. I'll show you guys the output of my catkin build. Thanks in advance.
image

astec_mav_framework

Has anybody managed to make this package work with any of the Asctec Quads Hardware (e.g. Pelican)?
It seems like there is no proper documentation for that. Any help is really appreciated!

Query : Regarding the Reference Trajectory Input

We are working on using MoveIt! for planning collision free trajectory for our UAV. We found that this package perfectly fills in the gap between MoveIt! and the low level controller on board the UAV. However as MoveIt! just outputs a trajectory with no accel / vel information, can this package still be used to generate attitude commands.

Use of steady_state_calculation.cpp

Hello ! I am trying to understand your MPC code and I don't understand the use of steady_state_calculation.cpp. What is it's use in the MPC algorithm ?

Delay compensation

Hi,

Did you compensate the delay for the calculation time of the MPC?

Thank you

drift off/diverge when yaw 90 degree

Hi! I am using the nonlinear MPC on a small drone controlled by Betaflight. I use RC signal to control the attitude and use vicon to estimate odometry. I did the system ID and some dynamic tuning and it hovers very accurately when have 0 degree yaw command. However, if I give command/pose a 90 degree yaw orientation, it turns to 90 degree and begin to drift like a spiral, then it reaches a sort of stable status and loiters. It is very strange because I have used this MPC on Pixhawk and M100, and they all flies fine. Any ideas why this is happening? Thanks.

Best regards,
Feng

Problem compiling

Hello,

I am running Ubuntu 16.04 with ROS kinetic. I wasn't able to compile with the liblapack-dev libraries as said in the instructions but after looking around in the CMakeLists of the nonlinear MPC I tried installing libopenblas-dev and the nonlinear MPC compiled.

The issue im having is with the Linear MPC, it hangs when compiling and never ends. I guess it has something to do with the cvxgen_solver but im not sure. Any help is welcome! Thanks!

Also when I run nonlinear mav_nonlinear_mpc_sim.launch I get the same assertion failed as in #4

[ INFO] [1489688585.790922587]: Created control interface for controller nonlinear_model_predictive_controller and RC ACI rc interface
nonlinear_mpc_node: /usr/include/boost/msm/front/state_machine_def.hpp:203: void boost::msm::front::state_machine_def<Derived, BaseState>::no_transition(const Event&, FSM&, int) [with FSM = boost::msm:: back::state_machine<mav_control_interface::state_machine::StateMachineDefinition, boost::msm:: back::mpl_graph_fsm_check>; Event = mav_control_interface::state_machine::OdometryWatchdog; Derived = mav_control_interface::state_machine::StateMachineDefinition; BaseState = boost::msm::front::default_base_state]: Assertion `false' failed.

Question about moment of inertia.

First of all, thank you for this awesome framework!!
I know this is not an issue of this framework but i need some advice to find moment of inertia.
As far as i know, it can be calculated from many way such as

  1. by measuring the period of oscillation.
  2. by accurate solidworks model or cad model.

These above ways can achieve accurate Ixx,Iyy,Izz but required hard work on every payload change.
I have heard from someone that we can also estimate from fitted curve transfer function by excite the respect axis. This way is good enough to use in this framework? Any guide would be appreciate.
Thank you.

Starting the project mav_control using ACADOtoolkit in ROS- Link to a simple example

Dear developers and researchers!

This work looks greate!, so I decided to recover many concepts from this project. I have tested this project, but I found many missing packages on it. I tasted on Ubuntu 16.0 and Gazebo 7. I cannot run the project, the only one stuff I would like to test is the ACADOtoolkit in ROS. I only checked the controller package, but I cannot run it as well. Can anybody help me with a simple project working with ACADO and ROS. I appreciate it so much.

Greatings
Javier

catkin build error

`hussein@Lenovo-ideapad:~/catkin_ws$ catkin build

Profile: default
Extending: [env] /home/hussein/simulation/ros_catkin_ws/devel:/opt/ros/indigo
Workspace: /home/hussein/catkin_ws

Source Space: [exists] /home/hussein/catkin_ws/src
Log Space: [missing] /home/hussein/catkin_ws/logs
Build Space: [exists] /home/hussein/catkin_ws/build
Devel Space: [exists] /home/hussein/catkin_ws/devel
Install Space: [unused] /home/hussein/catkin_ws/install
DESTDIR: [unused] None

Devel Space Layout: linked
Install Space Layout: None

Additional CMake Args: -DCMAKE_BUILD_TYPE=Release
Additional Make Args: None
Additional catkin Make Args: None
Internal Make Job Server: True
Cache Job Environments: False

Whitelisted Packages: None
Blacklisted Packages: None

Workspace configuration appears valid.

NOTE: Forcing CMake to run for each package.

[build] Found '20' packages in 0.0 seconds.
[build] Updating package table.
Starting >>> catkin_tools_prebuild
Finished <<< catkin_tools_prebuild [ 1.2 seconds ]
Starting >>> catkin_simple
Starting >>> mav_msgs
Starting >>> rotors_comm
Starting >>> rotors_description
Finished <<< rotors_description [ 1.8 seconds ]
Starting >>> rotors_evaluation
Finished <<< catkin_simple [ 2.0 seconds ]
Starting >>> rqt_rotors
Finished <<< rotors_comm [ 3.7 seconds ]
Starting >>> eigen_catkin
Finished <<< rotors_evaluation [ 2.1 seconds ]
Finished <<< rqt_rotors [ 2.1 seconds ]
Finished <<< mav_msgs [ 4.3 seconds ]
Starting >>> mav_control_interface
Starting >>> mav_disturbance_observer
Starting >>> mav_lowlevel_attitude_controller


Warnings << eigen_catkin:make /home/hussein/catkin_ws/logs/eigen_catkin/build.make.000.log
abort: repository /home/hussein/catkin_ws/build/eigen_catkin/eigen_src-prefix/src/eigen_src not found!
abort: repository /home/hussein/catkin_ws/build/eigen_catkin/eigen_src-prefix/src/eigen_src not found!
CMake Warning at blas/CMakeLists.txt:32 (message):
No fortran compiler has been detected, the blas build will be incomplete.

cd /home/hussein/catkin_ws/build/eigen_catkin; catkin build --get-env eigen_catkin | catkin env -si /usr/bin/make --jobserver-fds=6,7 -j; cd -
..................................................................................................
Finished <<< eigen_catkin [ 14.2 seconds ]
Finished <<< mav_lowlevel_attitude_controller [ 20.2 seconds ]
Starting >>> planning_msgs
Finished <<< mav_disturbance_observer [ 21.6 seconds ]
Starting >>> rotors_control
Finished <<< planning_msgs [ 7.8 seconds ]
Starting >>> rotors_hil_interface


Errors << rotors_hil_interface:make /home/hussein/catkin_ws/logs/rotors_hil_interface/build.make.000.log
In file included from /home/hussein/catkin_ws/src/rotors_simulator/rotors_hil_interface/src/hil_sensor_level_interface.cpp:17:0:
/home/hussein/catkin_ws/src/rotors_simulator/rotors_hil_interface/include/rotors_hil_interface/hil_interface.h:22:37: fatal error: mavros_msgs/HilControls.h: No such file or directory
#include <mavros_msgs/HilControls.h>
^
compilation terminated.
make[2]: *** [CMakeFiles/rotors_hil_interface.dir/src/hil_sensor_level_interface.cpp.o] Error 1
make[1]: *** [CMakeFiles/rotors_hil_interface.dir/all] Error 2
make: *** [all] Error 2
cd /home/hussein/catkin_ws/build/rotors_hil_interface; catkin build --get-env rotors_hil_interface | catkin env -si /usr/bin/make --jobserver-fds=6,7 -j; cd -
................................................................................................
Failed << rotors_hil_interface:make [ Exited with code 2 ]
Failed <<< rotors_hil_interface [ 7.3 seconds ]
Abandoned <<< rotors_joy_interface [ Unrelated job failed ]
Abandoned <<< mav_linear_mpc [ Unrelated job failed ]
Abandoned <<< mav_nonlinear_mpc [ Unrelated job failed ]
Abandoned <<< rotors_gazebo_plugins [ Unrelated job failed ]
Abandoned <<< rotors_gazebo [ Unrelated job failed ]
Finished <<< rotors_control [ 25.7 seconds ]
Finished <<< mav_control_interface [ 50.4 seconds ]
[build] Summary: 13 of 19 packages succeeded.
[build] Ignored: 2 packages were skipped or are blacklisted.
[build] Warnings: 1 packages succeeded with warnings.
[build] Abandoned: 5 packages were abandoned.
[build] Failed: 1 packages failed.
[build] Runtime: 56.3 seconds total.
[build] Note: Workspace packages have changed, please re-source setup files to use them.`

reference trajectory linear MPC

Hello,
when we publish a command trajectory through waypoint_publisher, how is it processed? Let's say my horizon length is 10. The terget state values x_r (which I get by steady state calculation) are same for all instants? Or, the waypoints are calculated through some kind of interpolation between initial and desired points?
Thanks in advance
Sandeep

Identification of thrust in DJI drones

I am using the linear and non-linear MPC in a Matrice 210, but it is not clear to me how to send the thrust command to the DJI autopilot.

The output of the MPC is Newtons, and DJI SDK has not this option. In a different repository of the ETHZ-ASL(mav_dji_ros_interface) you explain how to use it with a Matrice 100, in this case, they use the thrust in percentage. For converting from Newtons to % they add an offset and multiply by a coefficient, but I don't understand how these values are calculated.

thrust_command = (+1)* thrust_offset_ + msg->thrust.z*thrust_coefficient_;

When using the values from the mav_dji_ros_interface repository I have a good performance but I have to set a different masss from the real one and the errors are quite high.

By the way, thank you very much for this open-source project it is very useful.

Errors from Custom MAVROS Node Install

Hi,

I've been working to install this repository and everything has gone well up until the point of installing the modified MAVROS node. I've been able to install the RotorS simulation as well as the packages within mav_control_rw and catkin build my workspace with no issues. The MAVROS node is the point where I'm stuck. Currently I've been following the general instructions to install MAVROS (under source installation). In the rosinstall file, I've replaced the default MAVROS repository url with the one pointing to the custom node, and then specified 'master' as the version. Otherwise, I finished following the steps provided and everything ran with no errors. Though, attempting to catkin build my workspace results in the following errors:

Errors     << mavros:make /home/nick/catkin_ws/logs/mavros/build.make.008.log                       
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_sensor_orientation.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘MAV_AUTOPILOT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/mavros_msgs/include/mavros_msgs/mavlink_convert.h:18,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:22,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_sensor_orientation.cpp:17:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:34:12: note:   ‘mavlink::minimal::MAV_AUTOPILOT’
 enum class MAV_AUTOPILOT : uint8_t
            ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_sensor_orientation.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘MAV_TYPE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: note: suggested alternative: ‘AIS_TYPE’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
                                        AIS_TYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘MAV_STATE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: note: suggested alternative: ‘MAV_FRAME’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
                                        MAV_FRAME
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘MAV_COMPONENT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: note: suggested alternative: ‘MAV_MODE’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
                                        MAV_MODE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:114:18: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
 mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type);
                  ^~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘MAV_AUTOPILOT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/mavros_msgs/include/mavros_msgs/mavlink_convert.h:18,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:22,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:34:12: note:   ‘mavlink::minimal::MAV_AUTOPILOT’
 enum class MAV_AUTOPILOT : uint8_t
            ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘MAV_TYPE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: note: suggested alternative: ‘AIS_TYPE’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
                                        AIS_TYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘MAV_STATE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: note: suggested alternative: ‘MAV_FRAME’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
                                        MAV_FRAME
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘MAV_COMPONENT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: note: suggested alternative: ‘MAV_MODE’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
                                        MAV_MODE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:114:18: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
 mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type);
                  ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:24:24: error: ‘mavlink::common::MAV_AUTOPILOT’ has not been declared
 using mavlink::common::MAV_AUTOPILOT;
                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:25:24: error: ‘mavlink::common::MAV_TYPE’ has not been declared
 using mavlink::common::MAV_TYPE;
                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:26:24: error: ‘mavlink::common::MAV_STATE’ has not been declared
 using mavlink::common::MAV_STATE;
                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:27:24: error: ‘mavlink::common::MAV_COMPONENT’ has not been declared
 using mavlink::common::MAV_COMPONENT;
                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:131:23: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(MAV_AUTOPILOT e)
                       ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:80:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::LANDING_TARGET_TYPE)’
 std::string to_string(mavlink::common::LANDING_TARGET_TYPE e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:131:23: error: ‘MAV_AUTOPILOT’ was not declared in this scope
 std::string to_string(MAV_AUTOPILOT e)
                       ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:131:23: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/mavros_msgs/include/mavros_msgs/mavlink_convert.h:18,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:22,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:34:12: note:   ‘mavlink::minimal::MAV_AUTOPILOT’
 enum class MAV_AUTOPILOT : uint8_t
            ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:192:23: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(MAV_TYPE e)
                       ^~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:80:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::LANDING_TARGET_TYPE)’
 std::string to_string(mavlink::common::LANDING_TARGET_TYPE e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:192:23: error: ‘MAV_TYPE’ was not declared in this scope
 std::string to_string(MAV_TYPE e)
                       ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:192:23: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/mavros_msgs/include/mavros_msgs/mavlink_convert.h:18,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:22,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:62:12: note:   ‘mavlink::minimal::MAV_TYPE’
 enum class MAV_TYPE : uint8_t
            ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:243:21: error: ‘MAV_TYPE’ was not declared in this scope
 std::string to_name(MAV_TYPE e)
                     ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:243:21: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/mavros_msgs/include/mavros_msgs/mavlink_convert.h:18,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:22,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:62:12: note:   ‘mavlink::minimal::MAV_TYPE’
 enum class MAV_TYPE : uint8_t
            ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:244:1: error: expected ‘,’ or ‘;’ before ‘{’ token
 {
 ^
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:280:23: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(MAV_STATE e)
                       ^~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:80:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::LANDING_TARGET_TYPE)’
 std::string to_string(mavlink::common::LANDING_TARGET_TYPE e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:280:23: error: ‘MAV_STATE’ was not declared in this scope
 std::string to_string(MAV_STATE e)
                       ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:280:23: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/mavros_msgs/include/mavros_msgs/mavlink_convert.h:18,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:22,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:139:12: note:   ‘mavlink::minimal::MAV_STATE’
 enum class MAV_STATE : uint8_t
            ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:584:23: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(MAV_COMPONENT e)
                       ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:431:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::GPS_FIX_TYPE)’
 std::string to_string(GPS_FIX_TYPE e)
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:584:23: error: ‘MAV_COMPONENT’ was not declared in this scope
 std::string to_string(MAV_COMPONENT e)
                       ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:584:23: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/mavros_msgs/include/mavros_msgs/mavlink_convert.h:18,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:22,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:19:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:158:12: note:   ‘mavlink::minimal::MAV_COMPONENT’
 enum class MAV_COMPONENT
            ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/enum_to_string.cpp:608:1: error: ‘MAV_TYPE’ does not name a type; did you mean ‘LC_CTYPE’?
 MAV_TYPE mav_type_from_str(const std::string &mav_type)
 ^~~~~~~~
 LC_CTYPE
make[2]: *** [CMakeFiles/mavros.dir/src/lib/enum_to_string.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
make[2]: *** [CMakeFiles/mavros.dir/src/lib/enum_sensor_orientation.cpp.o] Error 1
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:17:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘MAV_AUTOPILOT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/interface.h:37,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:28,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:17:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:34:12: note:   ‘mavlink::minimal::MAV_AUTOPILOT’
 enum class MAV_AUTOPILOT : uint8_t
            ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:17:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘MAV_TYPE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: note: suggested alternative: ‘AIS_TYPE’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
                                        AIS_TYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘MAV_STATE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: note: suggested alternative: ‘MAV_FRAME’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
                                        MAV_FRAME
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘MAV_COMPONENT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: note: suggested alternative: ‘MAV_MODE’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
                                        MAV_MODE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:114:18: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
 mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type);
                  ^~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_plugin.h:25,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros.h:24,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp:15:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘MAV_AUTOPILOT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/interface.h:37,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros.h:23,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp:15:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:34:12: note:   ‘mavlink::minimal::MAV_AUTOPILOT’
 enum class MAV_AUTOPILOT : uint8_t
            ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_plugin.h:25,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros.h:24,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp:15:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘MAV_TYPE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: note: suggested alternative: ‘AIS_TYPE’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
                                        AIS_TYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘MAV_STATE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: note: suggested alternative: ‘MAV_FRAME’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
                                        MAV_FRAME
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘MAV_COMPONENT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: note: suggested alternative: ‘MAV_MODE’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
                                        MAV_MODE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:114:18: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
 mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type);
                  ^~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:73:36: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_TYPE = mavlink::common::MAV_TYPE;
                                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:74:41: error: ‘MAV_AUTOPILOT’ in namespace ‘mavlink::common’ does not name a type
  using MAV_AUTOPILOT = mavlink::common::MAV_AUTOPILOT;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:75:41: error: ‘MAV_MODE_FLAG’ in namespace ‘mavlink::common’ does not name a type
  using MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:76:37: error: ‘MAV_STATE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_STATE = mavlink::common::MAV_STATE;
                                     ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:119:9: error: ‘MAV_TYPE’ does not name a type; did you mean ‘LC_CTYPE’?
  inline MAV_TYPE get_type() {
         ^~~~~~~~
         LC_CTYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:127:9: error: ‘MAV_AUTOPILOT’ does not name a type
  inline MAV_AUTOPILOT get_autopilot() {
         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_armed()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:139:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::SAFETY_ARMED);
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_hil_state()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:147:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::HIL_ENABLED);
                                         ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_ardupilotmega()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
                                          autopilot
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_px4()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::PX4 == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
                                autopilot
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp: In constructor ‘mavros::UAS::UAS()’:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:26:18: error: ‘MAV_TYPE’ has not been declared
  type(enum_value(MAV_TYPE::GENERIC)),
                  ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:27:23: error: ‘MAV_AUTOPILOT’ has not been declared
  autopilot(enum_value(MAV_AUTOPILOT::GENERIC)),
                       ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp: At global scope:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:91:39: error: ‘MAV_AUTOPILOT’ is not a member of ‘mavros::UAS’
 static uint64_t get_default_caps(UAS::MAV_AUTOPILOT ap_type)
                                       ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp: In member function ‘uint64_t mavros::UAS::get_capabilities()’:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:104:27: error: ‘get_autopilot’ was not declared in this scope
   return get_default_caps(get_autopilot());
                           ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:104:27: note: suggested alternative: ‘autopilot’
   return get_default_caps(get_autopilot());
                           ^~~~~~~~~~~~~
                           autopilot
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_data.cpp:104:42: error: ‘get_default_caps’ cannot be used as a function
   return get_default_caps(get_autopilot());
                                          ^
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_plugin.h:25:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros.h:24,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp:15:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:73:36: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_TYPE = mavlink::common::MAV_TYPE;
                                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:74:41: error: ‘MAV_AUTOPILOT’ in namespace ‘mavlink::common’ does not name a type
  using MAV_AUTOPILOT = mavlink::common::MAV_AUTOPILOT;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:75:41: error: ‘MAV_MODE_FLAG’ in namespace ‘mavlink::common’ does not name a type
  using MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:76:37: error: ‘MAV_STATE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_STATE = mavlink::common::MAV_STATE;
                                     ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:119:9: error: ‘MAV_TYPE’ does not name a type; did you mean ‘LC_CTYPE’?
  inline MAV_TYPE get_type() {
         ^~~~~~~~
         LC_CTYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:127:9: error: ‘MAV_AUTOPILOT’ does not name a type
  inline MAV_AUTOPILOT get_autopilot() {
         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_armed()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:139:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::SAFETY_ARMED);
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_hil_state()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:147:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::HIL_ENABLED);
                                         ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_plugin.h:25:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros.h:24,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp:15:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_ardupilotmega()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
                                          autopilot
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_px4()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::PX4 == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
                                autopilot
/home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp: In lambda function:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp:147:68: error: ‘mavlink::common::msg::HEARTBEAT’ has not been declared
    if (this->gcs_quiet_mode && msg->msgid != mavlink::common::msg::HEARTBEAT::MSG_ID &&
                                                                    ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp: In member function ‘void mavros::MavRos::log_connect_change(bool)’:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/mavros.cpp:371:37: error: ‘class mavros::UAS’ has no member named ‘get_autopilot’; did you mean ‘autopilot’?
  auto ap = utils::to_string(mav_uas.get_autopilot());
                                     ^~~~~~~~~~~~~
                                     autopilot
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:17:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘MAV_AUTOPILOT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/interface.h:37,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:28,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:17:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:34:12: note:   ‘mavlink::minimal::MAV_AUTOPILOT’
 enum class MAV_AUTOPILOT : uint8_t
            ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:17:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘MAV_TYPE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: note: suggested alternative: ‘AIS_TYPE’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
                                        AIS_TYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘MAV_STATE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: note: suggested alternative: ‘MAV_FRAME’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
                                        MAV_FRAME
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘MAV_COMPONENT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: note: suggested alternative: ‘MAV_MODE’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
                                        MAV_MODE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:114:18: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
 mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type);
                  ^~~~~~~~
make[2]: *** [CMakeFiles/mavros.dir/src/lib/uas_data.cpp.o] Error 1
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:73:36: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_TYPE = mavlink::common::MAV_TYPE;
                                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:74:41: error: ‘MAV_AUTOPILOT’ in namespace ‘mavlink::common’ does not name a type
  using MAV_AUTOPILOT = mavlink::common::MAV_AUTOPILOT;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:75:41: error: ‘MAV_MODE_FLAG’ in namespace ‘mavlink::common’ does not name a type
  using MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:76:37: error: ‘MAV_STATE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_STATE = mavlink::common::MAV_STATE;
                                     ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:119:9: error: ‘MAV_TYPE’ does not name a type; did you mean ‘LC_CTYPE’?
  inline MAV_TYPE get_type() {
         ^~~~~~~~
         LC_CTYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:127:9: error: ‘MAV_AUTOPILOT’ does not name a type
  inline MAV_AUTOPILOT get_autopilot() {
         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_armed()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:139:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::SAFETY_ARMED);
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_hil_state()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:147:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::HIL_ENABLED);
                                         ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_ardupilotmega()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
                                          autopilot
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_px4()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::PX4 == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
                                autopilot
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp: At global scope:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:176:39: warning: inline variables are only available with -std=c++1z or -std=gnu++1z
 static inline bool is_apm_copter(UAS::MAV_TYPE type)
                                       ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:176:39: error: ‘MAV_TYPE’ is not a member of ‘mavros::UAS’
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp: In member function ‘std::__cxx11::string mavros::UAS::str_mode_v10(uint8_t, uint32_t)’:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:187:31: error: ‘MAV_MODE_FLAG’ has not been declared
  if (!(base_mode & enum_value(MAV_MODE_FLAG::CUSTOM_MODE_ENABLED)))
                               ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:190:14: error: ‘get_type’ was not declared in this scope
  auto type = get_type();
              ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:190:14: note: suggested alternative:
In file included from /usr/include/boost/parameter/parameters.hpp:44:0,
                 from /usr/include/boost/parameter.hpp:11,
                 from /usr/include/boost/signals2/signal_type.hpp:32,
                 from /usr/include/boost/signals2.hpp:20,
                 from /opt/ros/melodic/include/tf2/buffer_core.h:37,
                 from /opt/ros/melodic/include/tf2_ros/buffer_interface.h:35,
                 from /opt/ros/melodic/include/tf2_ros/buffer.h:35,
                 from /opt/ros/melodic/include/tf2_ros/transform_listener.h:40,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:24,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:17:
/usr/include/boost/parameter/aux_/unwrap_cv_reference.hpp:50:8: note:   ‘boost::parameter::aux::get_type’
 struct get_type
        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:191:12: error: ‘get_autopilot’ was not declared in this scope
  auto ap = get_autopilot();
            ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:191:12: note: suggested alternative: ‘autopilot’
  auto ap = get_autopilot();
            ^~~~~~~~~~~~~
            autopilot
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:192:6: error: ‘MAV_AUTOPILOT’ has not been declared
  if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
      ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:193:25: error: ‘is_apm_copter’ cannot be used as a function
   if (is_apm_copter(type))
                         ^
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:195:20: error: ‘MAV_TYPE’ has not been declared
   else if (type == MAV_TYPE::FIXED_WING)
                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:197:20: error: ‘MAV_TYPE’ has not been declared
   else if (type == MAV_TYPE::GROUND_ROVER)
                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:199:20: error: ‘MAV_TYPE’ has not been declared
   else if (type == MAV_TYPE::SURFACE_BOAT)
                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:201:20: error: ‘MAV_TYPE’ has not been declared
   else if (type == MAV_TYPE::SUBMARINE)
                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:208:11: error: ‘MAV_AUTOPILOT’ has not been declared
  else if (MAV_AUTOPILOT::PX4 == ap)
           ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp: In member function ‘bool mavros::UAS::cmode_from_str(std::__cxx11::string, uint32_t&)’:
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:255:14: error: ‘get_type’ was not declared in this scope
  auto type = get_type();
              ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:255:14: note: suggested alternative:
In file included from /usr/include/boost/parameter/parameters.hpp:44:0,
                 from /usr/include/boost/parameter.hpp:11,
                 from /usr/include/boost/signals2/signal_type.hpp:32,
                 from /usr/include/boost/signals2.hpp:20,
                 from /opt/ros/melodic/include/tf2/buffer_core.h:37,
                 from /opt/ros/melodic/include/tf2_ros/buffer_interface.h:35,
                 from /opt/ros/melodic/include/tf2_ros/buffer.h:35,
                 from /opt/ros/melodic/include/tf2_ros/transform_listener.h:40,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:24,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:17:
/usr/include/boost/parameter/aux_/unwrap_cv_reference.hpp:50:8: note:   ‘boost::parameter::aux::get_type’
 struct get_type
        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:256:12: error: ‘get_autopilot’ was not declared in this scope
  auto ap = get_autopilot();
            ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:256:12: note: suggested alternative: ‘autopilot’
  auto ap = get_autopilot();
            ^~~~~~~~~~~~~
            autopilot
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:257:6: error: ‘MAV_AUTOPILOT’ has not been declared
  if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
      ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:258:25: error: ‘is_apm_copter’ cannot be used as a function
   if (is_apm_copter(type))
                         ^
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:260:20: error: ‘MAV_TYPE’ has not been declared
   else if (type == MAV_TYPE::FIXED_WING)
                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:262:20: error: ‘MAV_TYPE’ has not been declared
   else if (type == MAV_TYPE::GROUND_ROVER)
                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:264:20: error: ‘MAV_TYPE’ has not been declared
   else if (type == MAV_TYPE::SUBMARINE)
                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_stringify.cpp:267:11: error: ‘MAV_AUTOPILOT’ has not been declared
  else if (MAV_AUTOPILOT::PX4 == ap)
           ^~~~~~~~~~~~~
make[2]: *** [CMakeFiles/mavros.dir/src/lib/mavros.cpp.o] Error 1
make[2]: *** [CMakeFiles/mavros.dir/src/lib/uas_stringify.cpp.o] Error 1
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_timesync.cpp:17:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: error: ‘MAV_AUTOPILOT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_AUTOPILOT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:70:40: note: suggested alternative:
In file included from /home/nick/catkin_ws/devel/include/mavlink/v2.0/common/common.hpp:2290:0,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/mavlink_dialect.h:26,
                 from /home/nick/catkin_ws/src/mavros/libmavconn/include/mavconn/interface.h:37,
                 from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:28,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_timesync.cpp:17:
/home/nick/catkin_ws/devel/include/mavlink/v2.0/common/../minimal/minimal.hpp:34:12: note:   ‘mavlink::minimal::MAV_AUTOPILOT’
 enum class MAV_AUTOPILOT : uint8_t
            ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:29:0,
                 from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_timesync.cpp:17:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: error: ‘MAV_TYPE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:71:40: note: suggested alternative: ‘AIS_TYPE’
 std::string to_string(mavlink::common::MAV_TYPE e);
                                        ^~~~~~~~
                                        AIS_TYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: error: ‘MAV_STATE’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:72:40: note: suggested alternative: ‘MAV_FRAME’
 std::string to_string(mavlink::common::MAV_STATE e);
                                        ^~~~~~~~~
                                        MAV_FRAME
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘std::__cxx11::string mavros::utils::to_string’ redeclared as different kind of symbol
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:68:13: note: previous declaration ‘std::__cxx11::string mavros::utils::to_string(mavlink::common::MAV_SENSOR_ORIENTATION)’
 std::string to_string(mavlink::common::MAV_SENSOR_ORIENTATION e);
             ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: error: ‘MAV_COMPONENT’ is not a member of ‘mavlink::common’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:73:40: note: suggested alternative: ‘MAV_MODE’
 std::string to_string(mavlink::common::MAV_COMPONENT e);
                                        ^~~~~~~~~~~~~
                                        MAV_MODE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/utils.h:114:18: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
 mavlink::common::MAV_TYPE mav_type_from_str(const std::string &mav_type);
                  ^~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_timesync.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:73:36: error: ‘MAV_TYPE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_TYPE = mavlink::common::MAV_TYPE;
                                    ^~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:74:41: error: ‘MAV_AUTOPILOT’ in namespace ‘mavlink::common’ does not name a type
  using MAV_AUTOPILOT = mavlink::common::MAV_AUTOPILOT;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:75:41: error: ‘MAV_MODE_FLAG’ in namespace ‘mavlink::common’ does not name a type
  using MAV_MODE_FLAG = mavlink::common::MAV_MODE_FLAG;
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:76:37: error: ‘MAV_STATE’ in namespace ‘mavlink::common’ does not name a type
  using MAV_STATE = mavlink::common::MAV_STATE;
                                     ^~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:119:9: error: ‘MAV_TYPE’ does not name a type; did you mean ‘LC_CTYPE’?
  inline MAV_TYPE get_type() {
         ^~~~~~~~
         LC_CTYPE
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:127:9: error: ‘MAV_AUTOPILOT’ does not name a type
  inline MAV_AUTOPILOT get_autopilot() {
         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_armed()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:139:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::SAFETY_ARMED);
                                         ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::get_hil_state()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:147:41: error: ‘MAV_MODE_FLAG’ has not been declared
   return base_mode_ & utils::enum_value(MAV_MODE_FLAG::HIL_ENABLED);
                                         ^~~~~~~~~~~~~
In file included from /home/nick/catkin_ws/src/mavros/mavros/src/lib/uas_timesync.cpp:17:0:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_ardupilotmega()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:371:42: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::ARDUPILOTMEGA == get_autopilot();
                                          ^~~~~~~~~~~~~
                                          autopilot
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h: In member function ‘bool mavros::UAS::is_px4()’:
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:10: error: ‘MAV_AUTOPILOT’ has not been declared
   return MAV_AUTOPILOT::PX4 == get_autopilot();
          ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: error: ‘get_autopilot’ was not declared in this scope
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
/home/nick/catkin_ws/src/mavros/mavros/include/mavros/mavros_uas.h:378:32: note: suggested alternative: ‘autopilot’
   return MAV_AUTOPILOT::PX4 == get_autopilot();
                                ^~~~~~~~~~~~~
                                autopilot
make[2]: *** [CMakeFiles/mavros.dir/src/lib/uas_timesync.cpp.o] Error 1
make[1]: *** [CMakeFiles/mavros.dir/all] Error 2
make: *** [all] Error 2
cd /home/nick/catkin_ws/build/mavros; catkin build --get-env mavros | catkin env -si  /usr/bin/make --jobserver-fds=6,7 -j; cd -

I'm not sure if this is the correct way to go about installing the custom node, and I'm also not sure where to go from here.

Thank you for any help,
Nick

some problems when combining this project with the modified PX4 firmware"ethzasl_mav_px4"

hello, in the readme note it says that this project can work with PX4 firmware, i have tried and succeeded in the process. but i have got a problem that quadrotors with F330 model can't hover stably. the roll_pitch_yawrate_thrust calculated by the linear mpc was published to the modified mavros topic /mavros/setpoint_raw/roll_pitch_yawrate_thrust, but it changes too quick so the quadrotors can't hover. i think the reason may be that the model used in the linear mpc doesn't match with the PX4 quadrotors model or the roll_pitch_yawrate_thrust is published to the mavros topic too frequently. could you please give me some advice on how to make the quadrotors with F330 hover stably? thanks a lot!

catkin build errors

Hello,
I have compile errors below:

image
image

How can I fix them?

Ubuntu 16.04
ROS Kinetic

Error: process has died [pid 22759, exit code -11, cmd devel/lib/mav_linear_mpc/mav_linear_mpc_node odometry:=ground_truth/odometry

Hi,

I am facing this error:

process[hummingbird/mav_linear_mpc-1]: started with pid [22759]
[ INFO] [1618838511.976781472]: start initializing mav_disturbance_observer:KF
[ INFO] [1618838511.982472661]: mav_disturbance_observer:KF dynamic config is called successfully
[ INFO] [1618838512.089732276]: KF parameters loaded successfully
[ INFO] [1618838512.091881717]: state_covariance_: 
0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1   0
  0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0   0 0.1
[ INFO] [1618838512.092414855]: Kalman Filter Initialized!
[ INFO] [1618838512.152031754]: Linear MPC: Steady State calculation is initialized correctly
[ INFO] [1618838512.152621132]: A: 
         1          0          0    0.09995          0          0          0  0.0426219
         0          1          0          0    0.09995          0 -0.0417737          0
         0          0          1          0          0        0.1          0          0
         0          0          0      0.999          0          0          0   0.794857
         0          0          0          0      0.999          0  -0.771302          0
         0          0          0          0          0          1          0          0
         0          0          0          0          0          0   0.606531          0
         0          0          0          0          0          0          0   0.647405
[ INFO] [1618838512.152912682]: B: 
          0  0.00542006           0
-0.00606806           0           0
          0           0     0.00495
          0    0.157882           0
  -0.175898           0           0
          0           0         0.1
   0.335286           0           0
          0    0.303891           0
[ INFO] [1618838512.153121789]: B_d: 
0.00494836          0          0
         0 0.00494836          0
         0          0    0.00495
 0.0999505          0          0
         0  0.0999505          0
         0          0        0.1
         0          0          0
         0          0          0
[ INFO] [1618838512.153471097]: Linear MPC: initialized correctly
[ INFO] [1618838512.385890028]: Linear MPC: Tuning parameters updated...
[ INFO] [1618838512.386254503]: diag(Q) = 
40 40 60 20 20 25 20 20
[ INFO] [1618838512.386620070]: diag(R) = 
35 35  2
[ INFO] [1618838512.387137912]: diag(R_delta) = 
    0.3    0.3 0.0025
[ INFO] [1618838512.388042858]: Q_final = 
  426.97        0        0  106.425        0        0        0  102.467
       0  422.018        0        0  101.431        0  -90.394        0
       0        0  563.584        0        0   111.51        0        0
 106.425        0        0  107.637        0        0        0  101.807
       0  101.431        0        0  102.542        0 -88.5021        0
       0        0   111.51        0        0  111.486        0        0
       0  -90.394        0        0 -88.5021        0   134.11        0
 102.467        0        0  101.807        0        0        0  164.115
[ INFO] [1618838512.627594266]: Created control interface for controller linear_model_predictive_controller and RC ACI rc interface
[hummingbird/mav_linear_mpc-1] process has died [pid 22759, exit code -11, cmd /home/ubuntu/catkin_ethz_controller_ws/devel/lib/mav_linear_mpc/mav_linear_mpc_node odometry:=ground_truth/odometry __name:=mav_linear_mpc __log:=/home/ubuntu/.ros/log/0f0fe9de-a112-11eb-9a83-95eaa68aef5f/hummingbird-mav_linear_mpc-1.log].
log file: /home/ubuntu/.ros/log/0f0fe9de-a112-11eb-9a83-95eaa68aef5f/hummingbird-mav_linear_mpc-1*.log
[hummingbird/mav_linear_mpc-1] restarting process

while running:
roslaunch mav_linear_mpc mav_linear_mpc.launcnamespace:=hummingbird

Details:
I am running this code repo on a raspberri pi 4. I wrote a C++ code to receive the attitude data from High Level processor and send motor speeds to the high level processor using serial port. Then fused the attitude with position data getting from VICON to generate odometry and publishing it on /hummingbird/ground_truth/odometry, also a Joy message for /hummingbird/rc topic. This error happens either when the RC is 'on' (setting rc[0]=1) or when I try to send point to /hummingbird/command/pose.

I guess the problem comes when the code wants to start the 'state_machine_' but I am not sure how.

[question] Asctec ROS package

Hello!

Thanks for making this package available publicly! Quick questions:

  • How do you go about normalizing the output Thrust so that the command is compatible with asctec_mav_framework?
  • Alternatively, which asctec ros package do you use with mav_control_rw?

Thanks!

Mathematics Behind the Attitude Controller

Hello! Thank you for good work.
I'm trying to understand the mathematics behind the attitude controller but there are certain aspects that I can't relate to the proposed block diagram for the control algorithm.
In theory, the input to the model should be the relationships between the angular velocities (thrust, and moments on the axes). To find the corresponding angular velocities would need (if I understand) the allocation matrix but I do not see this reflected in the code. The attitude controller gives directly to the motor plugin the reference angular velocity.
I see there are two functions that perform these operations: PIDAttitudeController::CalculateRotorVelocities and PIDAttitudeController::ComputeDesiredAngularAcc, but I can't identify how they are related.
Can someone help me clarify the question please? @alexmillane @ffurrer @ZacharyTaylor

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.