mavlink / mavros

MAVLink to ROS gateway with proxy for Ground Control Station
Other
879 stars 989 forks source link

sensor_msgs/FluidPressure and mavros/global_position/rel_alt do not works #1430

Open Cristian-wp opened 4 years ago

Cristian-wp commented 4 years ago

@vooon please help

Hello, I am trying to get the complete set of parameters that I can see in QGC in the parameter HIGRES_IMU. I know that most of these parameters are inside imu_pub topics so I have tried to use them. For what concern ~imu/data (sensor_msgs/Imu) all works perfectly, but when I use ~imu/atm_pressure (sensor_msgs/FluidPressure) the topic do not start and no values are displayed. I know that the sensor work because it change correctly in QGC. If I plot the connection with rqt_graph I can see the topic imu/data, but not the pressure one.

When I do roslaunch I can not see the parameter loaded, so I think that is the problem, but I do not understand how to add it.

I thinks I have to modify px4_config.yaml, but how?

The same problem is for mavros/global_position/rel_alt. Can someone help me with this problem(if is possible step by step)? If there is even another solution without Mavros it will be ok, but I need a tutorial about it, because I am not so expert in this field :( Thank you in advance.

Cristian

MAVROS version and platform

Mavros: 1.1.0 ROS: Melodic Ubuntu: 18.04

Autopilot type and version

[ ] ArduPilot [ x ] PX4

Version: 1.10

Node logs

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/cmd/use_comp_id_system_control: False
 * /mavros/conn/heartbeat_rate: 1.0
 * /mavros/conn/system_time_rate: 1.0
 * /mavros/conn/timeout: 10.0
 * /mavros/conn/timesync_rate: 10.0
 * /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
 * /mavros/distance_sensor/hrlv_ez4_pub/id: 0
 * /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
 * /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/laser_1_sub/id: 3
 * /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/laser_1_sub/subscriber: True
 * /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
 * /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
 * /mavros/distance_sensor/lidarlite_pub/id: 1
 * /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
 * /mavros/distance_sensor/lidarlite_pub/send_tf: True
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/sonar_1_sub/id: 2
 * /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/fake_gps/eph: 2.0
 * /mavros/fake_gps/epv: 2.0
 * /mavros/fake_gps/fix_type: 3
 * /mavros/fake_gps/geo_origin/alt: 408.0
 * /mavros/fake_gps/geo_origin/lat: 47.3667
 * /mavros/fake_gps/geo_origin/lon: 8.55
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/mocap_transform: True
 * /mavros/fake_gps/satellites_visible: 5
 * /mavros/fake_gps/tf/child_frame_id: fix
 * /mavros/fake_gps/tf/frame_id: map
 * /mavros/fake_gps/tf/listen: False
 * /mavros/fake_gps/tf/rate_limit: 10.0
 * /mavros/fake_gps/tf/send: False
 * /mavros/fake_gps/use_mocap: True
 * /mavros/fake_gps/use_vision: False
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: /dev/ttyACM0:57600
 * /mavros/gcs_url: udp://@127.0.0.1
 * /mavros/global_position/child_frame_id: base_link
 * /mavros/global_position/frame_id: map
 * /mavros/global_position/gps_uere: 1.0
 * /mavros/global_position/rot_covariance: 99999.0
 * /mavros/global_position/tf/child_frame_id: base_link
 * /mavros/global_position/tf/frame_id: map
 * /mavros/global_position/tf/global_frame_id: earth
 * /mavros/global_position/tf/send: False
 * /mavros/global_position/use_relative_alt: True
 * /mavros/image/frame_id: px4flow
 * /mavros/imu/angular_velocity_stdev: 0.0003490659 // 0...
 * /mavros/imu/frame_id: base_link
 * /mavros/imu/linear_acceleration_stdev: 0.0003
 * /mavros/imu/magnetic_stdev: 0.0
 * /mavros/imu/orientation_stdev: 1.0
 * /mavros/landing_target/camera/fov_x: 2.0071286398
 * /mavros/landing_target/camera/fov_y: 2.0071286398
 * /mavros/landing_target/image/height: 480
 * /mavros/landing_target/image/width: 640
 * /mavros/landing_target/land_target_type: VISION_FIDUCIAL
 * /mavros/landing_target/listen_lt: False
 * /mavros/landing_target/mav_frame: LOCAL_NED
 * /mavros/landing_target/target_size/x: 0.3
 * /mavros/landing_target/target_size/y: 0.3
 * /mavros/landing_target/tf/child_frame_id: camera_center
 * /mavros/landing_target/tf/frame_id: landing_target
 * /mavros/landing_target/tf/listen: False
 * /mavros/landing_target/tf/rate_limit: 10.0
 * /mavros/landing_target/tf/send: True
 * /mavros/local_position/frame_id: map
 * /mavros/local_position/tf/child_frame_id: base_link
 * /mavros/local_position/tf/frame_id: map
 * /mavros/local_position/tf/send: False
 * /mavros/local_position/tf/send_fcu: False
 * /mavros/mission/pull_after_gcs: True
 * /mavros/mocap/use_pose: True
 * /mavros/mocap/use_tf: False
 * /mavros/odometry/fcu/odom_child_id_des: base_link
 * /mavros/odometry/fcu/odom_parent_id_des: map
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682
 * /mavros/px4flow/ranger_max_range: 5.0
 * /mavros/px4flow/ranger_min_range: 0.3
 * /mavros/safety_area/p1/x: 1.0
 * /mavros/safety_area/p1/y: 1.0
 * /mavros/safety_area/p1/z: 1.0
 * /mavros/safety_area/p2/x: -1.0
 * /mavros/safety_area/p2/y: -1.0
 * /mavros/safety_area/p2/z: -1.0
 * /mavros/setpoint_accel/send_force: False
 * /mavros/setpoint_attitude/reverse_thrust: False
 * /mavros/setpoint_attitude/tf/child_frame_id: target_attitude
 * /mavros/setpoint_attitude/tf/frame_id: map
 * /mavros/setpoint_attitude/tf/listen: False
 * /mavros/setpoint_attitude/tf/rate_limit: 50.0
 * /mavros/setpoint_attitude/use_quaternion: False
 * /mavros/setpoint_position/mav_frame: LOCAL_NED
 * /mavros/setpoint_position/tf/child_frame_id: target_position
 * /mavros/setpoint_position/tf/frame_id: map
 * /mavros/setpoint_position/tf/listen: False
 * /mavros/setpoint_position/tf/rate_limit: 50.0
 * /mavros/setpoint_raw/thrust_scaling: 1.0
 * /mavros/setpoint_velocity/mav_frame: LOCAL_NED
 * /mavros/startup_px4_usb_quirk: True
 * /mavros/sys/disable_diag: False
 * /mavros/sys/min_voltage: 10.0
 * /mavros/target_component_id: 1
 * /mavros/target_system_id: 1
 * /mavros/tdr_radio/low_rssi: 40
 * /mavros/time/time_ref_source: fcu
 * /mavros/time/timesync_avg_alpha: 0.6
 * /mavros/time/timesync_mode: MAVLINK
 * /mavros/vibration/frame_id: base_link
 * /mavros/vision_pose/tf/child_frame_id: vision_estimate
 * /mavros/vision_pose/tf/frame_id: odom
 * /mavros/vision_pose/tf/listen: False
 * /mavros/vision_pose/tf/rate_limit: 10.0
 * /mavros/vision_speed/listen_twist: True
 * /mavros/vision_speed/twist_cov: True
 * /mavros/wheel_odometry/child_frame_id: base_link
 * /mavros/wheel_odometry/count: 2
 * /mavros/wheel_odometry/frame_id: odom
 * /mavros/wheel_odometry/send_raw: True
 * /mavros/wheel_odometry/send_twist: False
 * /mavros/wheel_odometry/tf/child_frame_id: base_link
 * /mavros/wheel_odometry/tf/frame_id: odom
 * /mavros/wheel_odometry/tf/send: False
 * /mavros/wheel_odometry/use_rpm: False
 * /mavros/wheel_odometry/vel_error: 0.1
 * /mavros/wheel_odometry/wheel0/radius: 0.05
 * /mavros/wheel_odometry/wheel0/x: 0.0
 * /mavros/wheel_odometry/wheel0/y: -0.15
 * /mavros/wheel_odometry/wheel1/radius: 0.05
 * /mavros/wheel_odometry/wheel1/x: 0.0
 * /mavros/wheel_odometry/wheel1/y: 0.15
 * /rosdistro: melodic
 * /rosversion: 1.14.5

NODES
  /
    mavros (mavros/mavros_node)

ROS_MASTER_URI=http://localhost:11311

process[mavros-1]: started with pid [4805]
[ INFO] [1589554522.411623334]: FCU URL: /dev/ttyACM0:57600
[ INFO] [1589554522.413191992]: serial0: device: /dev/ttyACM0 @ 57600 bps
[ INFO] [1589554522.415473086]: GCS URL: udp://@127.0.0.1
[ INFO] [1589554522.415766257]: udp1: Bind address: 0.0.0.0:14555
[ INFO] [1589554522.415875572]: udp1: Remote address: 127.0.0.1:14550
[ INFO] [1589554522.424827313]: Plugin 3dr_radio loaded
[ INFO] [1589554522.426182957]: Plugin 3dr_radio initialized
[ INFO] [1589554522.426312808]: Plugin actuator_control loaded
[ INFO] [1589554522.428274802]: Plugin actuator_control initialized
[ INFO] [1589554522.430754973]: Plugin adsb loaded
[ INFO] [1589554522.432987246]: Plugin adsb initialized
[ INFO] [1589554522.433148142]: Plugin altitude loaded
[ INFO] [1589554522.434023325]: Plugin altitude initialized
[ INFO] [1589554522.434128825]: Plugin cam_imu_sync loaded
[ INFO] [1589554522.434518083]: Plugin cam_imu_sync initialized
[ INFO] [1589554522.434656610]: Plugin command loaded
[ INFO] [1589554522.438550092]: Plugin command initialized
[ INFO] [1589554522.438696267]: Plugin companion_process_status loaded
[ INFO] [1589554522.440334351]: Plugin companion_process_status initialized
[ INFO] [1589554522.440485441]: Plugin debug_value loaded
[ INFO] [1589554522.442983688]: Plugin debug_value initialized
[ INFO] [1589554522.443024494]: Plugin distance_sensor blacklisted
[ INFO] [1589554522.443135613]: Plugin fake_gps loaded
[ INFO] [1589554522.449044279]: Plugin fake_gps initialized
[ INFO] [1589554522.449191781]: Plugin ftp loaded
[ INFO] [1589554522.453365738]: Plugin ftp initialized
[ INFO] [1589554522.453495517]: Plugin global_position loaded
[ INFO] [1589554522.460999463]: Plugin global_position initialized
[ INFO] [1589554522.461115049]: Plugin gps_rtk loaded
[ INFO] [1589554522.462240478]: Plugin gps_rtk initialized
[ INFO] [1589554522.462358194]: Plugin hil loaded
[ INFO] [1589554522.468575906]: Plugin hil initialized
[ INFO] [1589554522.468703807]: Plugin home_position loaded
[ INFO] [1589554522.470778427]: Plugin home_position initialized
[ INFO] [1589554522.471013474]: Plugin imu loaded
[ INFO] [1589554522.475597871]: Plugin imu initialized
[ INFO] [1589554522.475707891]: Plugin landing_target loaded
[ INFO] [1589554522.482133768]: Plugin landing_target initialized
[ INFO] [1589554522.482233681]: Plugin local_position loaded
[ INFO] [1589554522.485326287]: Plugin local_position initialized
[ INFO] [1589554522.485448904]: Plugin log_transfer loaded
[ INFO] [1589554522.487387472]: Plugin log_transfer initialized
[ INFO] [1589554522.487475080]: Plugin manual_control loaded
[ INFO] [1589554522.489450890]: Plugin manual_control initialized
[ INFO] [1589554522.489559557]: Plugin mocap_pose_estimate loaded
[ INFO] [1589554522.491328130]: Plugin mocap_pose_estimate initialized
[ INFO] [1589554522.491443558]: Plugin mount_control loaded
[ INFO] [1589554522.493190975]: Plugin mount_control initialized
[ INFO] [1589554522.493285478]: Plugin obstacle_distance loaded
[ INFO] [1589554522.495124079]: Plugin obstacle_distance initialized
[ INFO] [1589554522.495198484]: Plugin odom loaded
[ INFO] [1589554522.497686260]: Plugin odom initialized
[ INFO] [1589554522.497782491]: Plugin onboard_computer_status loaded
[ INFO] [1589554522.499028316]: Plugin onboard_computer_status initialized
[ INFO] [1589554522.499178837]: Plugin param loaded
[ INFO] [1589554522.501133299]: Plugin param initialized
[ INFO] [1589554522.501283922]: Plugin px4flow loaded
[ INFO] [1589554522.504706694]: Plugin px4flow initialized
[ INFO] [1589554522.504732465]: Plugin rangefinder blacklisted
[ INFO] [1589554522.504880364]: Plugin rc_io loaded
[ INFO] [1589554522.507151475]: Plugin rc_io initialized
[ INFO] [1589554522.507173326]: Plugin safety_area blacklisted
[ INFO] [1589554522.507297008]: Plugin setpoint_accel loaded
[ INFO] [1589554522.508903704]: Plugin setpoint_accel initialized
[ INFO] [1589554522.509078608]: Plugin setpoint_attitude loaded
[ INFO] [1589554522.514121908]: Plugin setpoint_attitude initialized
[ INFO] [1589554522.514252050]: Plugin setpoint_position loaded
[ INFO] [1589554522.521690518]: Plugin setpoint_position initialized
[ INFO] [1589554522.521814170]: Plugin setpoint_raw loaded
[ INFO] [1589554522.526106456]: Plugin setpoint_raw initialized
[ INFO] [1589554522.526246305]: Plugin setpoint_trajectory loaded
[ INFO] [1589554522.528958037]: Plugin setpoint_trajectory initialized
[ INFO] [1589554522.529077399]: Plugin setpoint_velocity loaded
[ INFO] [1589554522.531815933]: Plugin setpoint_velocity initialized
[ INFO] [1589554522.532052848]: Plugin sys_status loaded
[ INFO] [1589554522.538312034]: Plugin sys_status initialized
[ INFO] [1589554522.538470654]: Plugin sys_time loaded
[ INFO] [1589554522.541100273]: TM: Timesync mode: MAVLINK
[ INFO] [1589554522.541706464]: Plugin sys_time initialized
[ INFO] [1589554522.541781790]: Plugin trajectory loaded
[ INFO] [1589554522.544318972]: Plugin trajectory initialized
[ INFO] [1589554522.544434118]: Plugin vfr_hud loaded
[ INFO] [1589554522.544812860]: Plugin vfr_hud initialized
[ INFO] [1589554522.544848000]: Plugin vibration blacklisted
[ INFO] [1589554522.544965030]: Plugin vision_pose_estimate loaded
[ INFO] [1589554522.548738650]: Plugin vision_pose_estimate initialized
[ INFO] [1589554522.548844427]: Plugin vision_speed_estimate loaded
[ INFO] [1589554522.550524649]: Plugin vision_speed_estimate initialized
[ INFO] [1589554522.550673764]: Plugin waypoint loaded
[ INFO] [1589554522.553322315]: Plugin waypoint initialized
[ INFO] [1589554522.553365440]: Plugin wheel_odometry blacklisted
[ INFO] [1589554522.553486132]: Plugin wind_estimation loaded
[ INFO] [1589554522.553952906]: Plugin wind_estimation initialized
[ INFO] [1589554522.554010943]: Autostarting mavlink via USB on PX4
[ INFO] [1589554522.554167519]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1589554522.554202193]: Built-in MAVLink package version: 2020.5.5
[ INFO] [1589554522.554237567]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1589554522.554256901]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1589554522.637083226]: IMU: Scaled IMU message used.
[ WARN] [1589554522.640124661]: GP: No GPS fix
[ INFO] [1589554522.669057882]: IMU: High resolution IMU detected!
[ INFO] [1589554522.669971741]: IMU: Attitude quaternion IMU detected!
[ INFO] [1589554522.941547893]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1589554522.982411406]: IMU: Scaled IMU message used.
[ INFO] [1589554522.987363511]: IMU: High resolution IMU detected!
[ INFO] [1589554522.987956899]: IMU: Attitude quaternion IMU detected!
[ERROR] [1589554523.536722228]: FCU: Onboard controller lost
[ INFO] [1589554523.604757667]: FCU: Onboard controller regained
[ INFO] [1589554523.945683954]: VER: 1.1: Capabilities         0x000000000000e4ef
[ INFO] [1589554523.945772513]: VER: 1.1: Flight software:     01090100 (c92c90d4d9000000)
[ INFO] [1589554523.945819483]: VER: 1.1: Middleware software: 01090100 (c92c90d4d9000000)
[ INFO] [1589554523.945868578]: VER: 1.1: OS software:         071c00ff (423371c7d4012e72)
[ INFO] [1589554523.945901792]: VER: 1.1: Board hardware:      00000011
[ INFO] [1589554523.945933149]: VER: 1.1: VID/PID:             26ac:0011
[ INFO] [1589554523.945989115]: VER: 1.1: UID:                 3137510c39343835
[ WARN] [1589554523.946307054]: CMD: Unexpected command 520, result 0

Diagnostics

header: 
  seq: 15
  stamp: 
    secs: 1589554843
    nsecs: 864979384
  frame_id: ''
status: 
  - 
    level: 0
    name: "mavros: FCU connection"
    message: "connected"
    hardware_id: "/dev/ttyACM0:57600"
    values: 
      - 
        key: "Received packets:"
        value: "2534"
      - 
        key: "Dropped packets:"
        value: "0"
      - 
        key: "Buffer overruns:"
        value: "0"
      - 
        key: "Parse errors:"
        value: "0"
      - 
        key: "Rx sequence number:"
        value: "220"
      - 
        key: "Tx sequence number:"
        value: "0"
      - 
        key: "Rx total bytes:"
        value: "143220"
      - 
        key: "Tx total bytes:"
        value: "3613"
      - 
        key: "Rx speed:"
        value: "36911.000000"
      - 
        key: "Tx speed:"
        value: "850.000000"
  - 
    level: 2
    name: "mavros: GPS"
    message: "No satellites"
    hardware_id: "/dev/ttyACM0:57600"
    values: 
      - 
        key: "Satellites visible"
        value: "0"
      - 
        key: "Fix type"
        value: "0"
      - 
        key: "EPH (m)"
        value: "99.99"
      - 
        key: "EPV (m)"
        value: "99.99"
  - 
    level: 0
    name: "mavros: Heartbeat"
    message: "Normal"
    hardware_id: "/dev/ttyACM0:57600"
    values: 
      - 
        key: "Heartbeats since startup"
        value: "6"
      - 
        key: "Frequency (Hz)"
        value: "0.919988"
      - 
        key: "Vehicle type"
        value: "Hexarotor"
      - 
        key: "Autopilot type"
        value: "PX4 Autopilot"
      - 
        key: "Mode"
        value: "MANUAL"
      - 
        key: "System status"
        value: "Standby"
  - 
    level: 2
    name: "mavros: System"
    message: "Sensor health"
    hardware_id: "/dev/ttyACM0:57600"
    values: 
      - 
        key: "Sensor present"
        value: "0x000E002F"
      - 
        key: "Sensor enabled"
        value: "0x0021000F"
      - 
        key: "Sensor health"
        value: "0x000E002F"
      - 
        key: "3D gyro"
        value: "Ok"
      - 
        key: "3D accelerometer"
        value: "Ok"
      - 
        key: "3D magnetometer"
        value: "Ok"
      - 
        key: "absolute pressure"
        value: "Ok"
      - 
        key: "rc receiver"
        value: "Fail"
      - 
        key: "AHRS subsystem health"
        value: "Fail"
      - 
        key: "CPU Load (%)"
        value: "44.1"
      - 
        key: "Drop rate (%)"
        value: "0.0"
      - 
        key: "Errors comm"
        value: "0"
      - 
        key: "Errors count #1"
        value: "0"
      - 
        key: "Errors count #2"
        value: "0"
      - 
        key: "Errors count #3"
        value: "0"
      - 
        key: "Errors count #4"
        value: "0"
  - 
    level: 0
    name: "mavros: Battery"
    message: "Normal"
    hardware_id: "/dev/ttyACM0:57600"
    values: 
      - 
        key: "Voltage"
        value: "65.54"
      - 
        key: "Current"
        value: "-0.0"
      - 
        key: "Remaining"
        value: "-1.0"
  - 
    level: 0
    name: "mavros: Time Sync"
    message: "Normal"
    hardware_id: "/dev/ttyACM0:57600"
    values: 
      - 
        key: "Timesyncs since startup"
        value: "65"
      - 
        key: "Frequency (Hz)"
        value: "9.975201"
      - 
        key: "Last RTT (ms)"
        value: "1.682330"
      - 
        key: "Mean RTT (ms)"
        value: "1.282566"
      - 
        key: "Last remote time (s)"
        value: "27537.755183000"
      - 
        key: "Estimated time offset (s)"
        value: "1589527306.097930193"
---

Check ID

OK. I got messages from 1:1.

---
Received 6548 messages, from 1 addresses
sys:comp   list of messages
  1:1     0, 129, 2, 4, 1, 140, 141, 147, 24, 26, 30, 31, 32, 36, 74, 331, 77, 83, 340, 230, 105, 111, 241, 116, 245

My program

#include "ros/ros.h"
#include "geometry_msgs/Vector3.h"

#include "mavros_msgs/State.h"                          // FCU state - ~state

#include "std_msgs/Float64.h"                             // Relative altitude - ~global_position/rel_alt
                                                        // Compass heading in degrees - ~global_position/compass_hdg
#include "sensor_msgs/Temperature.h"
#include "sensor_msgs/Imu.h"
#include "sensor_msgs/FluidPressure.h"

mavros_msgs::State current_state;
void state_cb(const mavros_msgs::State::ConstPtr &msg){
    current_state = *msg;
}

void chatterBAROCallback(const sensor_msgs::FluidPressure::ConstPtr &msgBaro)
{
   ROS_INFO("\n BARO-id: %i \n BARO-height[m]: %f \n \n\n",msgBaro->header.seq, msgBaro->fluid_pressure);
}

void chatterGlobPosCallback(const std_msgs::Float64::ConstPtr &msgGlobPos)
{
   ROS_INFO("\n Relative altitude[m]: %f \n \n\n",msgGlobPos->data );
}

void chatterIMUCallback(const sensor_msgs::Imu::ConstPtr& msgIMU)
{
  ROS_INFO("\n Orientation X_list: %f \n Orientation Y_lis: %f \n Orientation Z_lis: %f \n\n", msgIMU->linear_acceleration.x,msgIMU->linear_acceleration.y,msgIMU->linear_acceleration.z);
}

int main(int argc, char **argv){

    ros::init(argc, argv, "imu_node");

    ros::NodeHandle nh;

    ros::Subscriber state_sub = nh.subscribe<mavros_msgs::State>("mavros/state", 10, state_cb);
    ros::Subscriber imu_sub = nh.subscribe("/mavros/imu/data", 1000,chatterIMUCallback);
    ros::Subscriber baro_sub = nh.subscribe<sensor_msgs::FluidPressure>("mavros/imu/atm_pressure", 1000,chatterBAROCallback);
    ros::Subscriber GlobPos_sub =nh.subscribe<std_msgs::Float64>("mavros/global_position/rel_alt", 1000,chatterGlobPosCallback);

    ros::Rate rate(20); //Hz

    // wait for FCU connection
    while(ros::ok() && !current_state.connected){
        ros::spinOnce();
        rate.sleep();
        if(current_state.connected){
            //ROS_INFO(" FCU Connected \n");    
        }
    }
    while(ros::ok() && current_state.connected){
        ros::spinOnce();
        rate.sleep();
    }
    return 0;
}
dayjaby commented 4 years ago

but when I use ~imu/atm_pressure (sensor_msgs/FluidPressure)

In https://github.com/mavlink/mavros/blob/master/mavros/src/plugins/imu.cpp only ~imu/static_pressure and ~imu/diff_pressure are listed. The wiki ros documentation is not always up-to-date and most of the time it is easier to look in the source code directly and see which topics are created.