mavlink / mavros

MAVLink to ROS gateway with proxy for Ground Control Station
Other
875 stars 988 forks source link

Setpoint_raw with bit mask 4067(VX VX PZ)not working properly. #1074

Closed eleboss closed 5 years ago

eleboss commented 6 years ago

Issue details

Dear team,

I am currently using setpoint_raw/localto control my drone indoor with a tfmini rangefinder. But when using setpoint_raw/local to control the VX VY and PZ with bitmask4067, strange things happen: I can switch to OFFBOARD mode and ARM the drone, however, the drone just stay on the ground with no movement and the propeller keep static(Usually, when ARMED, the propellers should rotate)

In the real world I done the following test: control vx, vy, z, y -> 3043 (0xBE3):stay on the ground, propeller rotate control vx, vy, z -> 4067 (0xFE3): stay on the ground, propeller keep static control vx, vy, z, y_rate -> 2019 (0x7E3):stay on the ground, propeller rotate control vx, vy, vz, y -> 3015 (0xBC7):working properly

and I also check basically all issues in google and github, but still couldn't figure out why this happened.

In order the further confirm the problem, I try the simulation SILT in gazebo.with same code. and same thing happen, but this time I get more information, control vx, vy, z, y -> 3043 (0xBE3):stay on the ground, propeller rotate with :WARN [mavlink] force setpoint not supported control vx, vy, z -> 4067 (0xFE3): stay on the ground, propeller keep static with WARN [mavlink] force setpoint not supported control vx, vy, z, y_rate -> 2019 (0x7E3):stay on the ground, propeller rotate with WARN [mavlink] force setpoint not supported control vx, vy, vz, y -> 3015 (0xBC7):working properly with no WARN

I am using the latest(1.8.0) version of PX4. From my viewpoint, It should work. and the https://github.com/PX4/Firmware/issues/7068 comfirmed that. An I wrong about something?

My real world setup: DJIF550 + pixhawk4 + benewake TFmini rangefinder + GPS I am doing a indoor test, so the GPS can't provide position feedback, but the rangefinder can provide the Z axis feedback, and I can directly check that by using rostopic echo /mavros/local_position/odom the position of z is accurately changed with z movement.

BTW, many references mentioned that setpoint_raw/target_local is a loop back topic, while my setpoint_raw/target_local never return anything at anytime, It this normal?

I really can't figure out this by myself, please help me to debug this. If any information is needed, please let me know.

Best regard!

MY code

I change the PositionTarget.IGNORE_* to test multiple bitmask.

    position_pub = rospy.Publisher('mavros/setpoint_raw/local', PositionTarget, queue_size=1)
    stamp = rospy.get_rostime()

    raw_msg = PositionTarget(coordinate_frame=PositionTarget.FRAME_LOCAL_NED,
                             type_mask=
                                       PositionTarget.IGNORE_PX + PositionTarget.IGNORE_PY + PositionTarget.IGNORE_VZ +
                                       PositionTarget.IGNORE_AFX + PositionTarget.IGNORE_AFY + PositionTarget.IGNORE_AFZ +
                                        PositionTarget.IGNORE_YAW_RATE +PositionTarget.FORCE,

                             yaw = output_yaw)
    raw_msg.header.stamp = stamp
    raw_msg.velocity.x = 0.0
    raw_msg.velocity.z = 0.0                          
    raw_msg.position.z = 1
    position_pub.publish(raw_msg)

I use rostopic echo /mavros/setpoint_raw/local to check the output, usually it looks like:

header: 
  seq: 128
  stamp: 
    secs: 1534585680
    nsecs: 509064912
  frame_id: ''
coordinate_frame: 1
type_mask: 4067
position: 
  x: 0.0
  y: 0.0
  z: 1.0
velocity: 
  x: 0.0
  y: 0.0
  z: 0.0
acceleration_or_force: 
  x: 0.0
  y: 0.0
  z: 0.0
yaw: -0.321090996265
yaw_rate: 0.0

The offboard code is very simple code,just keep calling the mode set service and keep arming.

MAVROS version and platform

Mavros: 0.24.0 ROS: Kinetic 1.12.13 Ubuntu: 16.04

Autopilot type and version

[ ] ArduPilot [this!] PX4

Version: In the real world: Pixhawk4 with 1.8.0 version In simulation: git clone from the latest Firmware of PX4 github and use: make posix_sitl_default gazebo to init the simulation.

Node logs

in the simulation

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: udp://:14540@127....
 * /mavros/gcs_url: 
 * /mavros/global_position/child_frame_id: base_link
 * /mavros/global_position/frame_id: map
 * /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.000349065850399
 * /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/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/estimator_type: 3
 * /mavros/odometry/frame_tf/desired_frame: ned
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682389136
 * /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_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: map
 * /mavros/vision_pose/tf/listen: False
 * /mavros/vision_pose/tf/rate_limit: 10.0
 * /mavros/vision_speed/listen_twist: False
 * /rosdistro: kinetic
 * /rosversion: 1.12.13

NODES
  /
    mavros (mavros/mavros_node)

auto-starting new master
process[master]: started with pid [31749]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to a3d62c66-a2ca-11e8-81ac-484d7eb149f3
process[rosout-1]: started with pid [31763]
started core service [/rosout]
process[mavros-2]: started with pid [31781]
[ INFO] [1534585185.587792400]: FCU URL: udp://:14540@127.0.0.1:14557
[ INFO] [1534585185.588803783]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1534585185.588833901]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1534585185.588887871]: GCS bridge disabled
[ INFO] [1534585185.595821455]: Plugin 3dr_radio loaded
[ INFO] [1534585185.597033887]: Plugin 3dr_radio initialized
[ INFO] [1534585185.597087328]: Plugin actuator_control loaded
[ INFO] [1534585185.599658155]: Plugin actuator_control initialized
[ INFO] [1534585185.600924618]: Plugin adsb loaded
[ INFO] [1534585185.603427454]: Plugin adsb initialized
[ INFO] [1534585185.603489617]: Plugin altitude loaded
[ INFO] [1534585185.604222390]: Plugin altitude initialized
[ INFO] [1534585185.604299973]: Plugin cam_imu_sync loaded
[ INFO] [1534585185.604751432]: Plugin cam_imu_sync initialized
[ INFO] [1534585185.604838957]: Plugin command loaded
[ INFO] [1534585185.608438186]: Plugin command initialized
[ INFO] [1534585185.608494717]: Plugin debug_value loaded
[ INFO] [1534585185.611834646]: Plugin debug_value initialized
[ INFO] [1534585185.611853874]: Plugin distance_sensor blacklisted
[ INFO] [1534585185.611929400]: Plugin fake_gps loaded
[ INFO] [1534585185.623018196]: Plugin fake_gps initialized
[ INFO] [1534585185.623106658]: Plugin ftp loaded
[ INFO] [1534585185.627520638]: Plugin ftp initialized
[ INFO] [1534585185.627591173]: Plugin global_position loaded
[ INFO] [1534585185.638627822]: Plugin global_position initialized
[ INFO] [1534585185.638701631]: Plugin hil loaded
[ INFO] [1534585185.648067347]: Plugin hil initialized
[ INFO] [1534585185.648165532]: Plugin home_position loaded
[ INFO] [1534585185.650906179]: Plugin home_position initialized
[ INFO] [1534585185.650995507]: Plugin imu loaded
[ INFO] [1534585185.656292365]: Plugin imu initialized
[ INFO] [1534585185.656359166]: Plugin local_position loaded
[ INFO] [1534585185.660088322]: Plugin local_position initialized
[ INFO] [1534585185.660166146]: Plugin manual_control loaded
[ INFO] [1534585185.662592810]: Plugin manual_control initialized
[ INFO] [1534585185.662685807]: Plugin mocap_pose_estimate loaded
[ INFO] [1534585185.666240181]: Plugin mocap_pose_estimate initialized
[ INFO] [1534585185.666296627]: Plugin obstacle_distance loaded
[ INFO] [1534585185.668069621]: Plugin obstacle_distance initialized
[ INFO] [1534585185.668149959]: Plugin odom loaded
[ INFO] [1534585185.671047635]: Plugin odom initialized
[ INFO] [1534585185.671121485]: Plugin param loaded
[ INFO] [1534585185.672553524]: Plugin param initialized
[ INFO] [1534585185.672609391]: Plugin px4flow loaded
[ INFO] [1534585185.677592205]: Plugin px4flow initialized
[ INFO] [1534585185.677608469]: Plugin rangefinder blacklisted
[ INFO] [1534585185.677671999]: Plugin rc_io loaded
[ INFO] [1534585185.680478666]: Plugin rc_io initialized
[ INFO] [1534585185.680502657]: Plugin safety_area blacklisted
[ INFO] [1534585185.680575448]: Plugin setpoint_accel loaded
[ INFO] [1534585185.683089475]: Plugin setpoint_accel initialized
[ INFO] [1534585185.683167924]: Plugin setpoint_attitude loaded
[ INFO] [1534585185.689884809]: Plugin setpoint_attitude initialized
[ INFO] [1534585185.689959042]: Plugin setpoint_position loaded
[ INFO] [1534585185.699757600]: Plugin setpoint_position initialized
[ INFO] [1534585185.699830261]: Plugin setpoint_raw loaded
[ INFO] [1534585185.706166642]: Plugin setpoint_raw initialized
[ INFO] [1534585185.706259831]: Plugin setpoint_velocity loaded
[ INFO] [1534585185.711836439]: Plugin setpoint_velocity initialized
[ INFO] [1534585185.711934534]: Plugin sys_status loaded
[ INFO] [1534585185.718251740]: Plugin sys_status initialized
[ INFO] [1534585185.718327341]: Plugin sys_time loaded
[ INFO] [1534585185.720596649]: TM: Timesync mode: MAVLINK
[ INFO] [1534585185.721030013]: Plugin sys_time initialized
[ INFO] [1534585185.721153385]: Plugin vfr_hud loaded
[ INFO] [1534585185.722117403]: Plugin vfr_hud initialized
[ INFO] [1534585185.722134621]: Plugin vibration blacklisted
[ INFO] [1534585185.722212416]: Plugin vision_pose_estimate loaded
[ INFO] [1534585185.727942572]: Plugin vision_pose_estimate initialized
[ INFO] [1534585185.728000688]: Plugin vision_speed_estimate loaded
[ INFO] [1534585185.730080529]: Plugin vision_speed_estimate initialized
[ INFO] [1534585185.730148663]: Plugin waypoint loaded
[ INFO] [1534585185.733108059]: Plugin waypoint initialized
[ INFO] [1534585185.733127472]: Autostarting mavlink via USB on PX4
[ INFO] [1534585185.733149563]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1534585185.733160654]: Built-in MAVLink package version: 2018.4.4
[ INFO] [1534585185.733187329]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1534585185.733199633]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1534585197.151419779]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1534585197.151513754]: IMU: High resolution IMU detected!
[ WARN] [1534585197.171134885]: TM: Clock skew detected (-1534585196.826479912 s). Hard syncing clocks.
[ INFO] [1534585198.053769230]: IMU: Attitude quaternion IMU detected!
[ INFO] [1534585198.072239196]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1534585198.073038536]: IMU: High resolution IMU detected!
[ INFO] [1534585198.073799430]: IMU: Attitude quaternion IMU detected!
[ INFO] [1534585199.073998796]: VER: 1.1: Capabilities         0x000000000000e4ef
[ INFO] [1534585199.074028687]: VER: 1.1: Flight software:     01080000 (00000000B01D5C12)
[ INFO] [1534585199.074046013]: VER: 1.1: Middleware software: 01080000 (00000000B01D5C12)
[ INFO] [1534585199.074061416]: VER: 1.1: OS software:         040f00ff (0000000042E2C593)
[ INFO] [1534585199.074074565]: VER: 1.1: Board hardware:      00000001
[ INFO] [1534585199.074093739]: VER: 1.1: VID/PID:             0000:0000
[ INFO] [1534585199.074106847]: VER: 1.1: UID:                 0000000100000002
[ WARN] [1534585199.256205679]: CMD: Unexpected command 520, result 0
[ INFO] [1534585208.072736717]: HP: requesting home position
[ INFO] [1534585213.073372334]: WP: mission received
[ WARN] [1534585230.243149475]: CMD: Unexpected command 176, result 1

Diagnostics

In the simulation:

    level: 0
    name: "mavros: Battery"
    message: "Normal"
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Voltage"
        value: "12.15"
      - 
        key: "Current"
        value: "-1.0"
      - 
        key: "Remaining"
        value: "100.0"
  - 
    level: 0
    name: "mavros: Time Sync"
    message: "Normal"
    hardware_id: "udp://:14540@127.0.0.1:14557"
    values: 
      - 
        key: "Timesyncs since startup"
        value: "51"
      - 
        key: "Frequency (Hz)"
        value: "9.975074"
      - 
        key: "Last dt (ms)"
        value: "-0.002919"
      - 
        key: "Mean dt (ms)"
        value: "-0.000198"
      - 
        key: "Last system time (s)"
        value: "5.488630000"
      - 
        key: "Time offset (s)"
        value: "1534586337.964153528"
---

SIMULATION TERMINAL

eleboss@eleboss:~/Firmware$ make posix_sitl_default gazebo
[  1%] Built target mixer_gen_6dof
[  1%] Built target mixer_gen
[  1%] Built target uorb_headers
[  3%] Built target df_driver_framework
[  3%] Built target git_ecl
[  3%] Built target ver_gen
[  3%] Built target git_gps_devices
[  4%] Built target git_driverframework
[  4%] Built target git_mavlink_v2
[  4%] Built target git_gazebo
[  4%] Built target logs_symlink
[  5%] Built target tinybson
[  5%] Built target perf
[  8%] Built target work_queue
[  8%] Built target ecl_airdata
[  9%] Built target ecl_attitude_fw
[ 10%] Built target ecl_geo
[ 25%] Built target uorb_msgs
[ 25%] Built target ecl_geo_lookup
[ 25%] Built target ecl_tecs
[ 25%] Built target ecl_validation
[ 26%] Built target mixer
[ 27%] Built target rc
[ 27%] Built target version
[ 27%] Built target generate_topic_listener
[ 27%] No forceconfigure step for 'sitl_gazebo'
[ 28%] Built target ecl_l1
[ 29%] Built target parameters
[ 29%] Performing configure step for 'sitl_gazebo'
-- install-prefix: /usr/local
[ 29%] Built target airspeed
[ 31%] Built target px4_daemon
[ 31%] Built target battery
[ 31%] Built target circuit_breaker
[ 31%] Built target conversion
[ 33%] Built target controllib
-- Boost version: 1.58.0
-- Found the following Boost libraries:
--   system
--   thread
--   timer
--   chrono
--   date_time
--   atomic
[ 34%] Built target mathlib
[ 35%] Built target drivers__device
[ 35%] Built target FlightTask
[ 35%] Built target pwm_limit
[ 35%] Built target pid
[ 35%] Built target terrain_estimation
-- Boost version: 1.58.0
[ 35%] Built target tunes
[ 36%] Built target platforms__common
[ 38%] Built target systemlib
[ 39%] Built target drivers_board
[ 39%] Built target launchdetection
[ 39%] Built target runway_takeoff
[ 40%] Built target drivers__airspeed
[ 41%] Built target px4_layer
[ 41%] Built target drivers__led
-- Building klt_feature_tracker without catkin
[ 41%] Built target FlightTaskUtility
-- Building OpticalFlow with OpenCV
[ 43%] Built target ecl_EKF
[ 44%] Built target FlightTaskManual
[ 45%] Built target FlightTaskAuto
[ 45%] Built target FlightTaskOffboard
-- catkin DISABLED
[ 46%] Built target modules__uORB
Gazebo version: 7.0
-- Using C++17 compiler
[ 46%] Built target drivers__ets_airspeed
[ 46%] Built target drivers__ms4525_airspeed
[ 47%] Built target drivers__ms5525_airspeed
[ 47%] Built target drivers__sdp3x_airspeed
[ 48%] Built target drivers__ll40ls
[ 48%] Built target drivers__mb12xx
-- Configuring done
[ 49%] Built target drivers__sf0x
[ 49%] Built target drivers__sf1xx
[ 50%] Built target drivers__srf02
[ 50%] Built target drivers__teraranger
[ 50%] Built target drivers__tfmini
[ 51%] Built target drivers__ulanding
[ 51%] Built target drivers__leddar_one
[ 51%] Built target drivers__vl53lxx
[ 52%] Built target drivers__batt_smbus
[ 53%] Built target drivers__camera_trigger
[ 53%] Built target drivers__pwm_out_sim
[ 54%] Built target drivers__gps
[ 55%] Built target drivers__vmount
[ 55%] Built target platforms__posix__drivers__tonealrmsim
[ 56%] Built target modules__sensors
[ 56%] Built target systemcmds__esc_calib
[ 57%] Built target systemcmds__led_control
[ 57%] Built target systemcmds__mixer
[ 57%] Built target systemcmds__motor_ramp
[ 58%] Built target systemcmds__param
[ 58%] Built target systemcmds__perf
[ 58%] Built target systemcmds__pwm
[ 58%] Built target systemcmds__reboot
[ 58%] Built target systemcmds__shutdown
[ 59%] Built target systemcmds__sd_bench
[ 59%] Built target systemcmds__top
[ 60%] Built target systemcmds__topic_listener
[ 60%] Built target systemcmds__tune_control
[ 60%] Built target systemcmds__ver
[ 60%] Built target drivers__sf0x__sf0x_tests
[ 60%] Built target lib__rc__rc_tests
[ 61%] Built target modules__commander__commander_tests
[ 62%] Built target lib__controllib__controllib_test
[ 63%] Built target modules__uORB__uORB_tests
[ 64%] Built target modules__mavlink__mavlink_tests
[ 65%] Built target platforms__posix__tests__hello
[ 65%] Built target platforms__posix__tests__hrt_test
[ 71%] Built target systemcmds__tests
[ 72%] Built target modules__camera_feedback
[ 73%] Built target platforms__posix__tests__vcdev_test
[ 74%] Built target modules__land_detector
[ 76%] Built target modules__events
[ 78%] Built target modules__commander
[ 78%] Built target modules__load_mon
[ 78%] Built target modules__replay
[ 80%] Built target modules__navigator
[ 81%] Built target drivers__ledsim
[ 81%] Built target modules__attitude_estimator_q
[ 84%] Built target modules__mavlink
[ 84%] Built target modules__ekf2
[ 85%] Built target modules__position_estimator_inav
[ 85%] Built target modules__wind_estimator
[ 87%] Built target modules__local_position_estimator
[ 87%] Built target modules__fw_att_control
[ 88%] Built target modules__gnd_att_control
[ 88%] Built target modules__fw_pos_control_l1
[ 88%] Built target modules__gnd_pos_control
[ 88%] Built target modules__mc_att_control
[ 89%] Built target modules__vtol_att_control
[ 89%] Built target modules__logger
[ 89%] Built target modules__dataman
[ 90%] Built target modules__landing_target_estimator
[ 90%] Built target modules__bottle_drop
[ 90%] Built target examples__rover_steering_control
[ 90%] Built target examples__uuv_example_app
[ 91%] Built target examples__segway
[ 91%] Built target examples__px4_simple_app
[ 91%] Built target examples__px4_mavlink_debug
[ 92%] Built target examples__fixedwing_control
[ 92%] Built target templates__module
[ 92%] Built target FlightTaskAutoMapper
[ 92%] Built target FlightTaskManualStabilized
[ 92%] Built target FlightTaskAutoFollowMe
[ 92%] Built target modules__simulator
[ 92%] Built target FlightTaskManualAltitude
[ 92%] Built target FlightTaskAutoLine
[ 92%] Built target drivers__accelsim
[ 92%] Built target drivers__airspeedsim
-- Generating done
[ 92%] Built target drivers__barosim
-- Build files have been written to: /home/eleboss/Firmware/build/posix_sitl_default/build_gazebo
[ 92%] Built target drivers__gpssim
[ 93%] Built target drivers__gyrosim
[ 93%] Built target FlightTaskManualAltitudeSmooth
[ 93%] Performing build step for 'sitl_gazebo'
[ 94%] Built target FlightTaskManualPosition
[ 95%] Built target FlightTaskOrbit
[ 95%] Built target FlightTaskManualPositionSmooth
[  8%] Built target std_msgs
[ 24%] Built target sensor_msgs
[ 28%] Built target nav_msgs
[ 35%] Built target mav_msgs
[ 36%] Built target sdf
[ 96%] Built target FlightTasks
[ 47%] Built target models_gen
[ 50%] Built target klt_feature_tracker
[ 97%] Built target modules__mc_pos_control
[ 53%] Built target gazebo_uuv_plugin
[ 57%] Built target gazebo_mavlink_interface
[ 60%] Built target gazebo_vision_plugin
[ 63%] Built target gazebo_multirotor_base_plugin
[ 98%] Built target px4
[ 65%] Built target gazebo_motor_model
[ 68%] Built target LiftDragPlugin
[ 71%] Built target gazebo_imu_plugin
[ 73%] Built target gazebo_gimbal_controller_plugin
[ 76%] Built target gazebo_irlock_plugin
[ 79%] Built target gazebo_controller_interface
[ 82%] Built target gazebo_geotagged_images_plugin
[ 84%] Built target gazebo_gps_plugin
[ 87%] Built target gazebo_sonar_plugin
[ 94%] Built target OpticalFlow
[ 97%] Built target gazebo_lidar_plugin
[100%] Built target gazebo_opticalflow_plugin
[ 98%] No install step for 'sitl_gazebo'
[ 98%] Completed 'sitl_gazebo'
[100%] Built target sitl_gazebo
SITL ARGS
sitl_bin: /home/eleboss/Firmware/build/posix_sitl_default/bin/px4
rcS_path: posix-configs/SITL/init/ekf2
debugger: none
program: gazebo
model: none
src_path: /home/eleboss/Firmware
build_path: /home/eleboss/Firmware/build/posix_sitl_default
empty model, setting iris as default
GAZEBO_PLUGIN_PATH :/home/eleboss/Firmware/build/posix_sitl_default/build_gazebo
GAZEBO_MODEL_PATH :/home/eleboss/Firmware/Tools/sitl_gazebo/models
LD_LIBRARY_PATH /home/eleboss/Documents/plane/devel/lib:/opt/ros/kinetic/lib:/opt/ros/kinetic/lib/x86_64-linux-gnu:/home/eleboss/Firmware/build/posix_sitl_default/build_gazebo
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 90.0.0.192
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[0] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[1] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[2] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[3] no joint control will be performed for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::propeller_joint] not found for channel[4] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::flap_left_joint] not found for channel[5] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::flap_right_joint] not found for channel[6] no joint control for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[7] no joint control will be performed for this channel.
[Msg] Using MAVLink protocol v2.0
SITL COMMAND: /home/eleboss/Firmware/build/posix_sitl_default/bin/px4 /home/eleboss/Firmware/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -t /home/eleboss/Firmware/test_data
INFO  [Unknown] Creating symlink /home/eleboss/Firmware/ROMFS/px4fmu_common -> /home/eleboss/Firmware/build/posix_sitl_default/tmp/rootfs/etc
145 WARNING: setRealtimeSched failed (not run as root?)

______  __   __    ___ 
| ___ \ \ \ / /   /   |
| |_/ /  \ V /   / /| |
|  __/   /   \  / /_| |
| |     / /^\ \ \___  |
\_|     \/   \/     |_/

px4 starting.

INFO  [Unknown] Calling startup script: bash etc/init.d-posix/rcS 0
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 90.0.0.192
INFO  [dataman] Unknown restart, data manager file './dataman' size is 11405132 bytes
INFO  [simulator] Waiting for initial data on UDP port 14560. Please start the flight simulator to proceed..
[Wrn] [Event.cc:87] Warning: Deleteing a connection right after creation. Make sure to save the ConnectionPtr from a Connect call
libGL error: failed to create drawable
INFO  [simulator] Got initial simulation data, running sim..
INFO  [init] Mixer: etc/mixers/quad_w.main.mix on /dev/pwm_output0
INFO  [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 14556 remote port 14550
INFO  [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14557 remote port 14540
INFO  [logger] logger started (mode=all)
INFO  [logger] Start file log
INFO  [logger] Opened log file: ./log/2018-08-18/09_58_58.ulg
INFO  [mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)
INFO  [Unknown] Startup script returned successfully
pxh> INFO  [mavlink] partner IP: 127.0.0.1
INFO  [ecl/EKF] EKF aligned, (pressure height, IMU buf: 22, OBS buf: 14)
INFO  [ecl/EKF] EKF GPS checks passed (WGS-84 origin set)
INFO  [ecl/EKF] EKF commencing GPS fusion
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motors, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motor_speed/0, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motor_speed/1, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motor_speed/2, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motor_speed/3, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/imu, deleting message. This warning is printed only once.

I am not sure weather it is suitable to ask this question at here or the PX4 stack, If it not suitable please tell me and I will switch to PX4 stack.

eleboss commented 6 years ago

UPDATE: I accidently make the setpoint_raw/target_local worked, when the drone is flying the data comes out! I force the drone the takeoff, and accidently saw the data comes out.

and the bitmask is 0

header: 
  seq: 2071
  stamp: 
    secs: 1534590628
    nsecs: 342651136
  frame_id: ''
coordinate_frame: 1
type_mask: 0
position: 
  x: -0.048215713352
  y: -0.488790094852
  z: 0.120928458869
velocity: 
  x: -0.945887446404
  y: -4.90971517563
  z: 0.391148298979
acceleration_or_force: 
  x: 0.0
  y: 0.0
  z: 0.0
yaw: -0.0
yaw_rate: -0.0
AlexisTM commented 6 years ago

The target_local topic is a feedback of the multicopter, not just a loopback and the type_mask is not filled in.

The two masks I use are the following:

eleboss commented 6 years ago

@AlexisTM Hi! Thanks for the very useful suggestions, I am currently using the velocity control, It works well, and the position control also work well in simulation environment.

But when use the combined mask, It just not working.

AlexisTM commented 6 years ago

The implementation for combined commands is a bit a spaghetti in the backend (PX4 Firmware).

NOTE: The Position setpoints in the PX4 Firmware are handled as a simple P controller. I have good results with an offboard PD controller.

eleboss commented 6 years ago

@AlexisTM Yes maybe the spaghetti implementation intorduced these bugs. Hope someone can solve it.

As you mentioned in the NOTE, the init parameter of Position setpoint actually not working well in my drone, My drone is a bit heavy. The drone swinged heavely when use the setpoint_raw/local in position control mode. The RANGEFINDERhttps://github.com/PX4/Firmware/issues/10264 bug may be the reason, I heven't done further test.

So, I implenent a cascade PID control by myself. First loop control the speed (setpoint_raw/local in speed mode), sencond loop control position, and with some pid tunning, It works well.

AlexisTM commented 6 years ago

You mean you are sending one velocity setpoint then a position setpoint? The new setpoint erases the precedent one, more likely the position control is not aggressive enough compared to the velocity control.

The Offboard mode is in rework, you can participate :)

eleboss commented 6 years ago

I just using the setpoint velocity, fully give up position. the cascade is implement in my code.

AlexisTM commented 6 years ago

Perfect ;)

OryWalker commented 6 years ago

Sorry if I'm necroing (a very minor one), but I had a setpoint_raw position script that was working fine, switching the type mask to velocity only, and now it won't respond to any of the published velocity set_points, UNLESS I very specifically manually arm, initiate takeoff via mavcmd and then switch to offboard, all via terminal. It will then follow the velocity setpoints. Before, it arms, switches to offboard, and then sits on the ground until it disarms.

Whereas with the other script (that only differs with respect to the type mask and the published setpoints being position rather than velocity) the drone would automatically take off. It would arm, switch to offboard, and then after a short wait would start following the setpoints.

I'm at my wits end at this point and I have no idea what I need to do to my script to get it to consistently follow the velocity commands.

petertheprocess commented 3 years ago

Is there any progress? I encountered the same problem when I use setpoint_raw/local to send a Vx Vy z cmd.

AlexisTM commented 3 years ago

This was 2 year ago, PX4 developed a lot in between.

Take a look at the Mavlink receiver part, I believe it should be able to do Vx, Vy and Z commands.

https://github.com/PX4/Firmware/blob/7d6f8dc8821989cb3d6764a6d85fcb2d839809d4/src/modules/mavlink/mavlink_receiver.cpp#L784-L953

If you really can't make it work, you can simply do a P controller over the altitude. That should be enough in the meantime.