Code Monkey home page Code Monkey logo

xtdrone's Introduction

介绍

XTDrone是基于PX4、ROS与Gazebo的无人机通用仿真平台。支持多旋翼飞行器(包含四轴和六轴)、固定翼飞行器、复合翼飞行器(包含quadplane,tailsitter和tiltrotor)与其他无人系统(如无人车、无人船与机械臂)。在XTDrone上验证过的算法,可以方便地部署到真实无人机上。

单机仿真架构如下图所示,详见论文

K. Xiao, S. Tan, G. Wang, X. An, X. Wang and X. Wang, "XTDrone: A Customizable Multi-rotor UAVs Simulation Platform," 2020 4th International Conference on Robotics and Automation Sciences (ICRAS), 2020, pp. 55-61, doi: 10.1109/ICRAS49812.2020.9134922.

预印版 arXiv:2003.09700

多机仿真架构如下图所示,详见论文

K. Xiao, L. Ma, S. Tan, Y. Cong , X. Wang, "Implementation of UAV Coordination Based on a Hierarchical Multi-UAV Simulation Platform," Advances in Guidance, Navigation and Control. Lecture Notes in Electrical Engineering, 2022, vol 644. Springer, Singapore. doi: 10.1007/978-981-15-8155-7_423

预印版 arXiv:2005.01125 (2020)

如果使用XTDrone用于学术论文的仿真验证,请引用上述的其中一篇论文。

在这个平台上,开发者可以快速验证算法。如:

双目SLAM

视觉惯性导航

视觉稠密重建

2D激光SLAM

3D激光SLAM

2D运动规划

3D运动规划

集群运动规划

目标检测与追踪

多机编队

多机精准降落

固定翼

复合翼

无人车

无人船

空中机械臂

教程

XTDrone使用文档

项目团队

  • 创立者:肖昆,谭劭昌
  • 指导老师:王祥科
  • 开发团队:肖昆,谭劭昌,王冠政,马澜,李玙珂,王齐鹏,胡新雨,吴欣宁,郑家驿,彭羽凡,郑子君,颜佳润,易丰,管若乔,胡文信,鲍毅,卓安,刘旭东,闵洁,刘传胪,阮慈棫

加入我们

欢迎广大无人机开发者们加入我们的团队,共同学习进步。如有意向,请把简历(包含对PX4 ROS与Gazebo的掌握情况)发到[email protected],让我们一起完善XTDrone仿真平台。

贡献者

非常感谢你们为XTDrone的贡献

陈科研,许江伟,卢永光,陈皋,孙长浩,聂莹,孔凡杰,李超然,李旭东,张华卿,林梓涵,何瑶

**机器人大赛无人机挑战赛仿真组

2022 **机器人大赛已完成比赛,比赛详情见官网,其中无人机挑战赛仿真组的平台使用XTDrone。2023无人机仿真组将继续由XTDrone团队筹备,届时欢迎大家积极报名,展示自己的风采。

“智航杯”全国无人机智能算法竞赛

“智航杯”全国无人机智能算法竞赛,由航空工业智航院、**光华科技基金会联合主办,目前正在报名阶段,比赛详情见官网,其中仿真赛项的平台使用XTDrone,欢迎大家积极报名,展示自己的风采。

合作

如果想与XTDrone团队建立合作,请联系肖昆[email protected]

xtdrone's People

Contributors

576140700 avatar aahuhu avatar brendaaaaaa avatar chaoranli20 avatar clumsyml avatar jessica7k avatar lanbotma avatar li-yuke avatar littlefairy-pyf avatar petertheprocess avatar robin-shaun avatar running-mars avatar softword-tt 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

xtdrone's Issues

你们的多机精准降落的代码写的有问题

precision_landing.py文件里面
写的是tfstamped = tfBuffer.lookup_transform('tag_'+vehicle_id, 'map', rospy.Time(0))
坐标系取反了
应该是
tfstamped = tfBuffer.lookup_transform('map', 'tag_'+vehicle_id, rospy.Time(0))
往前走直线的时候看不出
一转弯你们的就挂了
赶紧改了把别浪费更多人时间

Could i use the project in the ubuntu20.04 noetic?

Thank you for your work in the ROS.
I had read the md, and it show me that it can work in Kinetic and Melodic. Could i use the project in the noetic? And do i need to fix something in the XTDrone?
Thank you.

多无人机任务分配仿真问题

肖老师好,请问现在可以将Multi-UAV-Task-Assignment-Benchmark这个项目里用到的3种任务分配算法放在XTDrone这个平台进行仿真模拟吗?

如果可以的话,支持调用matlab编写的其他任务分配算法吗?(比如CBBA:Consensus Based Bundle Algorithm)

起飞问题

老师,我看我们的项目中的起飞过程都是键盘控制的,直接把这个过程写进飞控代码中可以吗?怎么实现呢?

编译使用你们的gazebo_ros包不能正确打开urdf模型了

这错误排查了我好久……
正常ROS自己装的gazebo打开urdf模型是好的,但我按教程删除了gazebo_ros包编译了你们的之后就打开urdf模型出错了

[robot_1/spawn_urdf-8] process has died [pid 25248, exit code 1, cmd /home/cui/catkin_ws/src/gazebo_ros_pkgs/gazebo_ros/scripts/spawn_model -urdf -model robot_1 -x -3.5 -y 3.5 -z 0.0 -Y 0.0 -param robot_description __name:=spawn_urdf __log:=/home/cui/.ros/log/5ce78aa0-54e8-11ed-abd5-0013ef5f1159/robot_1-spawn_urdf-8.log].

from tf.transformations import quaternion_from_euler
from tf.transformations import quaternion_from_euler
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf/init.py", line 30, in
from tf.transformations import quaternion_from_euler
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf/init.py", line 30, in
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf/init.py", line 30, in
from tf.transformations import quaternion_from_euler
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf/init.py", line 30, in
from tf2_ros import TransformException as Exception, ConnectivityException, LookupException, ExtrapolationException
from tf2_ros import TransformException as Exception, ConnectivityException, LookupException, ExtrapolationException
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_ros/init.py", line 38, in
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_ros/init.py", line 38, in
from tf2_ros import TransformException as Exception, ConnectivityException, LookupException, ExtrapolationException
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_ros/init.py", line 38, in
from tf2_ros import TransformException as Exception, ConnectivityException, LookupException, ExtrapolationException
from tf2_py import *
from tf2_py import *
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_ros/init.py", line 38, in
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_py/init.py", line 38, in
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_py/init.py", line 38, in
from tf2_py import *
File "/opt/ros/melodic/lib/python2.7/dist-packages/tf2_py/init.py", line 38, in
from ._tf2 import *
from ._tf2 import *
ImportError: dynamic module does not define module export function (PyInit__tf2)
ImportError: dynamic module does not define module export function (PyInit__tf2)

Onboard controller lost

Hi every body
I am trying to run "Target Detection and Tracking" simulation and was following user manual.
all thing seam be true but in simulation the robot has a unstable state and also in terminal i receive this error:
[ERROR] [1622446206.213580231, 2638.188000000]: FCU: Onboard controller lost
what is wrong?
another question is that the camera view has very lag! is it for my system performance?
thanks for you

提问

老师,这套程序有cpp程序的版本吗

sdf模型

肖老师,我打算做陆空无人机,想对您那个ris_realsense_camera sdf模型加四个地面轮子,但修改后gazebo就加载不出修改后的无人机模型了,想问您那个sdf模型是如何建立的?

Comments and code description.

Dear, first of all it is a great job was done here. I read your papers, it is very helpful and I hope you continue developing this work. I have only one suggestion in order to share, contribute, and discuss: I suggest adding comments for your code and some discussion, in addition a block diagram for different parts of code and the communication (including ros topics etc...). This should help many researchers and may be used by different universities. Thank you again.

cannot find -lpthreads

您好,我在按照教程执行到:make px4_sitl_default gazebo时,查看错误日志出现报错:cannot find -lpthreads,我本想改成-lpthread 可找不到在哪个CMakeLists.txt中修改,请问这个问题怎么解决比较合适?

keybords control

[ WARN] [1649764707.350161174, 243.640000000]: CMD: Unexpected command 176, result 1
WARN [commander] Failsafe enabled: no RC
WARN [navigator] Global position failure: fixed bank loiter
[ INFO] [1649764709.151677323, 245.440000000]: FCU: ARMED by Arm/Disarm component command
[ INFO] [1649764709.152816390, 245.440000000]: WP: reached #0
[ INFO] [1649764709.187624420, 245.474000000]: WP: reached #0
[ERROR] [1649764709.203981522, 245.492000000]: FCU: Failsafe enabled: no RC
[ INFO] [1649764709.252494950, 245.540000000]: FCU: Failsafe mode activated
[ INFO] [1649764709.296888714, 245.584000000]: WP: reached #0
[ERROR] [1649764709.303688324, 245.592000000]: FCU: Global position failure: fixed bank loiter

这是运行键盘控制飞行器时发生的错误,我z轴的速度都增加到5以上了,gazebo里的固定翼飞行器旋翼转了一会儿就停下来了,没飞起来

GPS denied

Have you guys tested the setup for GPS denied environments?

摄像头没有TF坐标。

我想请问一下是摄像头没有tf坐标吗。还是我哪里配置有问题。我发现没有坐标变换,没有办法去做vins

px4_traking.launch

could not find px4_tracking.launch anywhere
nor in ~/catkin_ws/src/darknet_ros/darknet_ros/launch
neither in
XTDrone/sensing/object_detection_and_tracking/darknet_ros/darknet_ros/launch

Why a coordinate frame transform is performed in the function construct_target in file multirotor_communication.py?

In the file, line 119 to line 129:

            target_raw_pose.position.x = -y
            target_raw_pose.position.y = x
            target_raw_pose.position.z = z

            target_raw_pose.velocity.x = -vy
            target_raw_pose.velocity.y = vx
            target_raw_pose.velocity.z = vz
            
            target_raw_pose.acceleration_or_force.x = afx
            target_raw_pose.acceleration_or_force.y = afy
            target_raw_pose.acceleration_or_force.z = afz

It's clear that the function do a coordinate frame transform here. But this transform lets MAV do a different behaviours in the Gazebo simulation, it's actually running at RFU coordinate frame. If we don't do the transform here, then the mav in the simulation is running at a right FLU coordinate frame.

VIO无法收到双目相机的数据

系统:WSL2-Ubuntu18

gazebo版本:
image

VINS-Fusion 官方DEMO已跑通

XTDrone键盘控制也没问题...

飞控EKF已按照教程设置为视觉定位:

	# GPS used
	#param set EKF2_AID_MASK 1
	# Vision used and GPS denied
	param set EKF2_AID_MASK 24

	# Barometer used for hight measurement
	#param set EKF2_HGT_MODE 0
	# Barometer denied and vision used for hight measurement
	param set EKF2_HGT_MODE 3

运行记录如下:

❯ roslaunch px4 indoor1.launch

... logging to /home/i/.ros/log/43386a1a-59c6-11ed-a997-00155df5312e/roslaunch-PC-i-5072.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://PC-i:46361/

SUMMARY
========

CLEAR PARAMETERS
 * /iris_0/mavros/

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

NODES
  /
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
  /iris_0/
    iris_0_spawn (gazebo_ros/spawn_model)
    mavros (mavros/mavros_node)
    sitl_0 (px4/px4)

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

setting /run_id to 43386a1a-59c6-11ed-a997-00155df5312e
process[rosout-1]: started with pid [5116]
started core service [/rosout]
process[gazebo-2]: started with pid [5124]
process[gazebo_gui-3]: started with pid [5128]
process[iris_0/sitl_0-4]: started with pid [5193]
INFO  [px4] Creating symlink /home/i/PX4_Firmware/ROMFS/px4fmu_common -> /home/i/.ros/sitl_iris_0/etc

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

px4 starting.

INFO  [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
process[iris_0/iris_0_spawn-5]: started with pid [5207]
INFO  [param] selected parameter default file eeprom/parameters_10016
[param] Loaded: eeprom/parameters_10016
process[iris_0/mavros-6]: started with pid [5216]
ERROR [param] Parameter COM_CPU_MAX not found.
INFO  [dataman] Unknown restart, data manager file './dataman' size is 11798680 bytes
INFO  [simulator] Waiting for simulator to accept connection on TCP port 4560
[ INFO] [1667294359.064611446]: FCU URL: udp://:24540@localhost:34580
[ INFO] [1667294359.066723358]: udp0: Bind address: 0.0.0.0:24540
[ INFO] [1667294359.066782111]: udp0: Remote address: 127.0.0.1:34580
[ INFO] [1667294359.066857601]: GCS bridge disabled
[ INFO] [1667294359.081819371]: Plugin 3dr_radio loaded
[ INFO] [1667294359.082780344]: Plugin 3dr_radio initialized
[ INFO] [1667294359.083002486]: Plugin actuator_control loaded
[ INFO] [1667294359.085407621]: Plugin actuator_control initialized
[ INFO] [1667294359.087258261]: Plugin adsb loaded
[ INFO] [1667294359.088746993]: Plugin adsb initialized
[ INFO] [1667294359.088835672]: Plugin altitude loaded
[ INFO] [1667294359.089467639]: Plugin altitude initialized
[ INFO] [1667294359.089530516]: Plugin cam_imu_sync loaded
[ INFO] [1667294359.089831105]: Plugin cam_imu_sync initialized
[ INFO] [1667294359.089890348]: Plugin camera loaded
[ INFO] [1667294359.090235994]: Plugin camera initialized
[ INFO] [1667294359.090347438]: Plugin command loaded
[ INFO] [1667294359.094173464]: Plugin command initialized
[ INFO] [1667294359.094280238]: Plugin companion_process_status loaded
[ INFO] [1667294359.095647667]: Plugin companion_process_status initialized
[ INFO] [1667294359.095769149]: Plugin debug_value loaded
[ INFO] [1667294359.097945790]: Plugin debug_value initialized
[ INFO] [1667294359.097985219]: Plugin distance_sensor blacklisted
[ INFO] [1667294359.098038985]: Plugin esc_status loaded
[ INFO] [1667294359.098593271]: Plugin esc_status initialized
[ INFO] [1667294359.098685690]: Plugin esc_telemetry loaded
[ INFO] [1667294359.099098401]: Plugin esc_telemetry initialized
[ INFO] [1667294359.099182100]: Plugin fake_gps loaded
[ INFO] [1667294359.105664167]: Plugin fake_gps initialized
[ INFO] [1667294359.105801610]: Plugin ftp loaded
[ INFO] [1667294359.108798863]: Plugin ftp initialized
[ INFO] [1667294359.108911647]: Plugin geofence loaded
[ INFO] [1667294359.110177502]: Plugin geofence initialized
[ INFO] [1667294359.110398165]: Plugin global_position loaded
[ INFO] [1667294359.117149708]: Plugin global_position initialized
[ INFO] [1667294359.117318708]: Plugin gps_input loaded
[ INFO] [1667294359.119012359]: Plugin gps_input initialized
[ INFO] [1667294359.119094919]: Plugin gps_rtk loaded
[ INFO] [1667294359.120224085]: Plugin gps_rtk initialized
[ INFO] [1667294359.120296090]: Plugin gps_status loaded
[ INFO] [1667294359.121277955]: Plugin gps_status initialized
[ INFO] [1667294359.121490898]: Plugin hil loaded
[ INFO] [1667294359.127430516]: Plugin hil initialized
[ INFO] [1667294359.127577690]: Plugin home_position loaded
[ INFO] [1667294359.129072415]: Plugin home_position initialized
[ INFO] [1667294359.129231265]: Plugin imu loaded
[ INFO] [1667294359.132635391]: Plugin imu initialized
[ INFO] [1667294359.132784959]: Plugin landing_target loaded
[ INFO] [1667294359.144832729]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1667294359.147197921]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1667294359.150905628]: Plugin landing_target initialized
[ INFO] [1667294359.151097777]: Plugin local_position loaded
[ INFO] [1667294359.160594889]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1667294359.160648377]: Plugin local_position initialized
[ INFO] [1667294359.160766082]: Plugin log_transfer loaded
[ INFO] [1667294359.164684804]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[ INFO] [1667294359.166136095]: Plugin log_transfer initialized
[ INFO] [1667294359.166239593]: Plugin mag_calibration_status loaded
[ INFO] [1667294359.166942072]: Plugin mag_calibration_status initialized
[ INFO] [1667294359.167102091]: Plugin manual_control loaded
[ INFO] [1667294359.169785060]: Plugin manual_control initialized
[ INFO] [1667294359.169905607]: Plugin mocap_pose_estimate loaded
[ INFO] [1667294359.172528355]: Plugin mocap_pose_estimate initialized
[ INFO] [1667294359.172646955]: Plugin mount_control loaded
[ INFO] [1667294359.174981631]: Plugin mount_control initialized
[ INFO] [1667294359.175095267]: Plugin nav_controller_output loaded
[ INFO] [1667294359.175478227]: Plugin nav_controller_output initialized
[ INFO] [1667294359.175559231]: Plugin obstacle_distance loaded
[ INFO] [1667294359.177383800]: Plugin obstacle_distance initialized
[ INFO] [1667294359.177488791]: Plugin odom loaded
[ INFO] [1667294359.179538038]: Plugin odom initialized
[ INFO] [1667294359.179632376]: Plugin onboard_computer_status loaded
[ INFO] [1667294359.181138475]: Plugin onboard_computer_status initialized
[ INFO] [1667294359.181400451]: Plugin param loaded
[ INFO] [1667294359.183075326]: Plugin param initialized
[ INFO] [1667294359.183160815]: Plugin play_tune loaded
[ INFO] [1667294359.184456337]: Plugin play_tune initialized
[ INFO] [1667294359.184542326]: Plugin px4flow loaded
[ INFO] [1667294359.189684784]: Plugin px4flow initialized
[ INFO] [1667294359.189893906]: Plugin rallypoint loaded
[ INFO] [1667294359.191553026]: Plugin rallypoint initialized
[ INFO] [1667294359.191598395]: Plugin rangefinder blacklisted
[ INFO] [1667294359.191754636]: Plugin rc_io loaded
[ INFO] [1667294359.193662117]: Plugin rc_io initialized
[ INFO] [1667294359.193702013]: Plugin safety_area blacklisted
[ INFO] [1667294359.193824479]: Plugin setpoint_accel loaded
[ INFO] [1667294359.195176920]: Plugin setpoint_accel initialized
[ INFO] [1667294359.195422472]: Plugin setpoint_attitude loaded
[ INFO] [1667294359.200252909]: Plugin setpoint_attitude initialized
[ INFO] [1667294359.200398865]: Plugin setpoint_position loaded
[ INFO] [1667294359.208777400]: Plugin setpoint_position initialized
[ INFO] [1667294359.208918274]: Plugin setpoint_raw loaded
[ INFO] [1667294359.214604508]: Plugin setpoint_raw initialized
[ INFO] [1667294359.214767399]: Plugin setpoint_trajectory loaded
[ INFO] [1667294359.217520762]: Plugin setpoint_trajectory initialized
[ INFO] [1667294359.217654727]: Plugin setpoint_velocity loaded
[ INFO] [1667294359.220858894]: Plugin setpoint_velocity initialized
[ INFO] [1667294359.221012716]: Plugin sys_status loaded
[ INFO] [1667294359.226702068]: Plugin sys_status initialized
[ INFO] [1667294359.226834674]: Plugin sys_time loaded
[ INFO] [1667294359.230122228]: TM: Timesync mode: MAVLINK
[ INFO] [1667294359.230378861]: TM: Not publishing sim time
[ INFO] [1667294359.231048277]: Plugin sys_time initialized
[ INFO] [1667294359.231173210]: Plugin terrain loaded
[ INFO] [1667294359.231496572]: Plugin terrain initialized
[ INFO] [1667294359.231583752]: Plugin trajectory loaded
[ INFO] [1667294359.233635273]: Plugin trajectory initialized
[ INFO] [1667294359.233698477]: Plugin tunnel loaded
[ INFO] [1667294359.234972731]: Plugin tunnel initialized
[ INFO] [1667294359.235056411]: Plugin vfr_hud loaded
[ INFO] [1667294359.235371883]: Plugin vfr_hud initialized
[ INFO] [1667294359.235427932]: Plugin vibration blacklisted
[ INFO] [1667294359.235513682]: Plugin vision_pose_estimate loaded
[ INFO] [1667294359.238823540]: Plugin vision_pose_estimate initialized
[ INFO] [1667294359.238906284]: Plugin vision_speed_estimate loaded
[ INFO] [1667294359.240583523]: Plugin vision_speed_estimate initialized
[ INFO] [1667294359.240704754]: Plugin waypoint loaded
[ INFO] [1667294359.243046797]: Plugin waypoint initialized
[ INFO] [1667294359.243106182]: Plugin wheel_odometry blacklisted
[ INFO] [1667294359.243236945]: Plugin wind_estimation loaded
[ INFO] [1667294359.243650732]: Plugin wind_estimation initialized
[ INFO] [1667294359.243794594]: Autostarting mavlink via USB on PX4
[ INFO] [1667294359.243849288]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1667294359.243890677]: Built-in MAVLink package version: 2022.8.8
[ INFO] [1667294359.243933752]: Known MAVLink dialects: common ardupilotmega ASLUAV AVSSUAS all development icarous matrixpilot paparazzi standard storm32 uAvionix ualberta
[ INFO] [1667294359.243974653]: MAVROS started. MY ID 1.240, TARGET ID 1.1
Warning [parser.cc:950] XML Element[friction], child of element[collision] not defined in SDF. Ignoring[friction]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[friction], child of element[collision] not defined in SDF. Ignoring[friction]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[friction], child of element[collision] not defined in SDF. Ignoring[friction]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
[ INFO] [1667294359.435258148]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1667294359.449140863]: Physics dynamic reconfigure ready.
[INFO] [1667294359.536306, 0.000000]: Loading model XML from ros parameter model_description
[INFO] [1667294359.544337, 0.000000]: Waiting for service /gazebo/spawn_sdf_model
[INFO] [1667294359.547759, 0.000000]: Calling service /gazebo/spawn_sdf_model
Warning [parser.cc:950] XML Element[parent], child of element[sensor] not defined in SDF. Ignoring[parent]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
[ WARN] [1667294359.964843403, 1814.889000000]: missing <robotNamespace>, set to default: /iris_0/
[ INFO] [1667294359.964921345, 1814.889000000]: <topicName> set to: /iris_0/imu_gazebo
[ INFO] [1667294359.964960910, 1814.889000000]: <frameName> set to: imu_link_stereo
[ INFO] [1667294359.965006546, 1814.889000000]: <updateRateHZ> set to: 500
[ INFO] [1667294359.965047394, 1814.889000000]: <gaussianNoise> set to: 0
[ INFO] [1667294359.965117435, 1814.889000000]: <xyzOffset> set to: 0 0 0
[ INFO] [1667294359.965262063, 1814.889000000]: <rpyOffset> set to: 0 -0 0
[INFO] [1667294359.969220, 1814.889000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1667294359.977051652, 1814.889000000]: Bumper Plugin: The 'robotNamespace' param was empty
[ INFO] [1667294359.977158817, 1814.889000000]: bumper plugin missing <frameName>, defaults to world
INFO  [simulator] Simulator connected on TCP port 4560.
INFO  [commander] LED: open /dev/led0 failed (22)
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 18570 remote port 14550
[iris_0/iris_0_spawn-5] process has finished cleanly
log file: /home/i/.ros/log/43386a1a-59c6-11ed-a997-00155df5312e/iris_0-iris_0_spawn-5*.log
INFO  [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 34580 remote port 24540
INFO  [mavlink] mode: Onboard, data rate: 4000 B/s on udp port 14280 remote port 14030
INFO  [logger] logger started (mode=all)
INFO  [logger] Start file log (type: full)
INFO  [logger] Opened full log file: ./log/2022-11-01/09_19_20.ulg
INFO  [mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)
INFO  [px4] Startup script returned successfully
[ INFO] [1667294360.279628266, 1815.049000000]: udp0: Remote address: 127.0.0.1:34580
[ INFO] [1667294360.279845981, 1815.049000000]: IMU: High resolution IMU detected!
[ INFO] [1667294360.311843924, 1815.081000000]: FCU: [logger] file:./log/2022-11-01/09_19_20.ulg
INFO  [mavlink] partner IP: 127.0.0.1
[ INFO] [1667294361.263282980, 1816.029000000]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1667294361.264207996, 1816.029000000]: IMU: High resolution IMU detected!
INFO  [ecl/EKF] 1772000: EKF aligned, (baro height, IMU buf: 22, OBS buf: 14)
INFO  [ecl/EKF] 1772000: reset position to last known position
INFO  [ecl/EKF] 1772000: reset velocity to zero
[ INFO] [1667294362.076579354, 1816.841000000]: IMU: Attitude quaternion IMU detected!
[ INFO] [1667294362.264894331, 1817.029000000]: GF: Using MISSION_ITEM_INT
[ INFO] [1667294362.264946435, 1817.029000000]: RP: Using MISSION_ITEM_INT
[ INFO] [1667294362.264990476, 1817.029000000]: WP: Using MISSION_ITEM_INT
[ INFO] [1667294362.265036480, 1817.029000000]: VER: 1.1: Capabilities         0x000000000000e4ef
[ INFO] [1667294362.265066776, 1817.029000000]: VER: 1.1: Flight software:     010b0000 (746b3124ab000000)
[ INFO] [1667294362.265101726, 1817.029000000]: VER: 1.1: Middleware software: 010b0000 (746b3124ab000000)
[ INFO] [1667294362.265132324, 1817.029000000]: VER: 1.1: OS software:         050a66ff (ec417d7466666801)
[ INFO] [1667294362.265173975, 1817.029000000]: VER: 1.1: Board hardware:      00000001
[ INFO] [1667294362.265202713, 1817.029000000]: VER: 1.1: VID/PID:             0000:0000
[ INFO] [1667294362.265241871, 1817.029000000]: VER: 1.1: UID:                 4954414c44494e4f
[ WARN] [1667294362.267973330, 1817.033000000]: CMD: Unexpected command 520, result 0
[ INFO] [1667294371.380943246, 1826.029000000]: HP: requesting home position
[ INFO] [1667294376.410561517, 1831.029000000]: RP: mission received
[ INFO] [1667294376.410768183, 1831.029000000]: WP: mission received
[ INFO] [1667294376.410921469, 1831.029000000]: GF: mission received
[ INFO] [1667294381.453842161, 1836.029000000]: HP: requesting home position

运行上述命令启动gazebo后,运行rostopic list结果如下:

❯ rostopic list

/clock
/diagnostics
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/performance_metrics
/gazebo/set_link_state
/gazebo/set_model_state
/gazebo/set_model_states
/iris_0/benchmarker/collision
/iris_0/imu_gazebo
/iris_0/mavlink/from
/iris_0/mavlink/gcs_ip
/iris_0/mavlink/to
/iris_0/mavros/actuator_control
/iris_0/mavros/adsb/send
/iris_0/mavros/adsb/vehicle
/iris_0/mavros/altitude
/iris_0/mavros/battery
/iris_0/mavros/battery2
/iris_0/mavros/cam_imu_sync/cam_imu_stamp
/iris_0/mavros/camera/image_captured
/iris_0/mavros/companion_process/status
/iris_0/mavros/debug_value/debug
/iris_0/mavros/debug_value/debug_vector
/iris_0/mavros/debug_value/named_value_float
/iris_0/mavros/debug_value/named_value_int
/iris_0/mavros/debug_value/send
/iris_0/mavros/esc_info
/iris_0/mavros/esc_status
/iris_0/mavros/esc_telemetry
/iris_0/mavros/estimator_status
/iris_0/mavros/extended_state
/iris_0/mavros/fake_gps/mocap/tf
/iris_0/mavros/geofence/waypoints
/iris_0/mavros/global_position/compass_hdg
/iris_0/mavros/global_position/global
/iris_0/mavros/global_position/gp_lp_offset
/iris_0/mavros/global_position/gp_origin
/iris_0/mavros/global_position/home
/iris_0/mavros/global_position/local
/iris_0/mavros/global_position/raw/fix
/iris_0/mavros/global_position/raw/gps_vel
/iris_0/mavros/global_position/raw/satellites
/iris_0/mavros/global_position/rel_alt
/iris_0/mavros/global_position/set_gp_origin
/iris_0/mavros/gps_input/gps_input
/iris_0/mavros/gps_rtk/rtk_baseline
/iris_0/mavros/gps_rtk/send_rtcm
/iris_0/mavros/gpsstatus/gps1/raw
/iris_0/mavros/gpsstatus/gps1/rtk
/iris_0/mavros/gpsstatus/gps2/raw
/iris_0/mavros/gpsstatus/gps2/rtk
/iris_0/mavros/hil/actuator_controls
/iris_0/mavros/hil/controls
/iris_0/mavros/hil/gps
/iris_0/mavros/hil/imu_ned
/iris_0/mavros/hil/optical_flow
/iris_0/mavros/hil/rc_inputs
/iris_0/mavros/hil/state
/iris_0/mavros/home_position/home
/iris_0/mavros/home_position/set
/iris_0/mavros/imu/data
/iris_0/mavros/imu/data_raw
/iris_0/mavros/imu/diff_pressure
/iris_0/mavros/imu/mag
/iris_0/mavros/imu/static_pressure
/iris_0/mavros/imu/temperature_baro
/iris_0/mavros/imu/temperature_imu
/iris_0/mavros/landing_target/lt_marker
/iris_0/mavros/landing_target/pose
/iris_0/mavros/landing_target/pose_in
/iris_0/mavros/local_position/accel
/iris_0/mavros/local_position/odom
/iris_0/mavros/local_position/pose
/iris_0/mavros/local_position/pose_cov
/iris_0/mavros/local_position/velocity_body
/iris_0/mavros/local_position/velocity_body_cov
/iris_0/mavros/local_position/velocity_local
/iris_0/mavros/log_transfer/raw/log_data
/iris_0/mavros/log_transfer/raw/log_entry
/iris_0/mavros/mag_calibration/report
/iris_0/mavros/mag_calibration/status
/iris_0/mavros/manual_control/control
/iris_0/mavros/manual_control/send
/iris_0/mavros/mission/reached
/iris_0/mavros/mission/waypoints
/iris_0/mavros/mocap/pose
/iris_0/mavros/mount_control/command
/iris_0/mavros/mount_control/orientation
/iris_0/mavros/mount_control/status
/iris_0/mavros/nav_controller_output
/iris_0/mavros/obstacle/send
/iris_0/mavros/odometry/in
/iris_0/mavros/odometry/out
/iris_0/mavros/onboard_computer/status
/iris_0/mavros/param/param_value
/iris_0/mavros/play_tune
/iris_0/mavros/px4flow/ground_distance
/iris_0/mavros/px4flow/raw/optical_flow_rad
/iris_0/mavros/px4flow/raw/send
/iris_0/mavros/px4flow/temperature
/iris_0/mavros/radio_status
/iris_0/mavros/rallypoint/waypoints
/iris_0/mavros/rc/in
/iris_0/mavros/rc/out
/iris_0/mavros/rc/override
/iris_0/mavros/setpoint_accel/accel
/iris_0/mavros/setpoint_attitude/cmd_vel
/iris_0/mavros/setpoint_attitude/thrust
/iris_0/mavros/setpoint_position/global
/iris_0/mavros/setpoint_position/global_to_local
/iris_0/mavros/setpoint_position/local
/iris_0/mavros/setpoint_raw/attitude
/iris_0/mavros/setpoint_raw/global
/iris_0/mavros/setpoint_raw/local
/iris_0/mavros/setpoint_raw/target_attitude
/iris_0/mavros/setpoint_raw/target_global
/iris_0/mavros/setpoint_raw/target_local
/iris_0/mavros/setpoint_trajectory/desired
/iris_0/mavros/setpoint_trajectory/local
/iris_0/mavros/setpoint_velocity/cmd_vel
/iris_0/mavros/setpoint_velocity/cmd_vel_unstamped
/iris_0/mavros/state
/iris_0/mavros/statustext/recv
/iris_0/mavros/statustext/send
/iris_0/mavros/target_actuator_control
/iris_0/mavros/terrain/report
/iris_0/mavros/time_reference
/iris_0/mavros/timesync_status
/iris_0/mavros/trajectory/desired
/iris_0/mavros/trajectory/generated
/iris_0/mavros/trajectory/path
/iris_0/mavros/tunnel/in
/iris_0/mavros/tunnel/out
/iris_0/mavros/vfr_hud
/iris_0/mavros/vision_pose/pose
/iris_0/mavros/vision_pose/pose_cov
/iris_0/mavros/vision_speed/speed_twist_cov
/iris_0/mavros/wind_estimation
/rosout
/rosout_agg
/tf
/tf_static

可以发现并没有发布/iris_0/stereo_camera/left/image_raw/iris_0/stereo_camera/right/image_raw话题数据

另外,在启动的gazebo中InsertTab中,也没有发现iris_stereo_camera模型
image

但是在目录中是可以发现iris_stereo_camera文件夹
image

启动vins节点后:
image
发现并没有获取到数据

运行输出如下:

❯ bash scripts/xtdrone_run_vio.sh
[ INFO] [1667294799.996004911]: init begins
... logging to /home/i/.ros/log/43386a1a-59c6-11ed-a997-00155df5312e/roslaunch-PC-i-5990.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

config_file: /home/i/catkin_ws/src/VINS-Fusion/config/xtdrone_sitl/px4_sitl_stereo_imu_config.yaml
USE_IMU: 1
IMU_TOPIC: /iris_0/imu_gazebo
result path ~/catkin_ws/vins_output/vio.csv
[ WARN] [1667294800.010580548]:  fix extrinsic param
camera number 2
[ INFO] [1667294800.011813010]: Synchronized sensors, fix time offset: 0
[ INFO] [1667294800.011872268]: ROW: 480 COL: 752
 exitrinsic cam 0
 0  0  1
-1  0  0
 0 -1  0
   0 0.12 -0.3
 exitrinsic cam 1
 0  0  1
-1  0  0
 0 -1  0
   0    0 -0.3
set g       0       0 9.81007
[ INFO] [1667294800.012140433]: reading paramerter of camera /home/i/catkin_ws/src/VINS-Fusion/config/xtdrone_sitl/cam0_pinhole_p1.yaml
[ INFO] [1667294800.013628707]: reading paramerter of camera /home/i/catkin_ws/src/VINS-Fusion/config/xtdrone_sitl/cam1_pinhole_p1.yaml
MULTIPLE_THREAD is 1
[ WARN] [1667294800.014195494]: waiting for image and imu...
started roslaunch server http://PC-i:43769/

SUMMARY
========

PARAMETERS
 * /rosdistro: melodic
 * /rosversion: 1.14.13

NODES
  /
    rvizvisualisation (rviz/rviz)

ROS_MASTER_URI=http://localhost:11311

process[rvizvisualisation-1]: started with pid [6033]

二维运动规划bug

~/XTDrone/motion_planning/2d/launch/2d_motion_planning.launch文件的行

 <arg name="motion_planning" default="/home/mch/XTDrone/motion_planning/2d/"/>

应改为

 <arg name="motion_planning" default="/home/mch/XTDrone/motion_planning/2d"/>

而不仅仅是改名字

多無人機編隊無法使用鍵盤控制

不好意思請問一下 當我在執行多無人機編隊的仿真時,啟用multirotor_keyboard_control.py這個檔案時,
執行 bash multi_vehicle_communication.sh的終端機會報下列錯誤:
請問該如何解決 ?

[ERROR] [1658131676.966918, 29.630000]: bad callback: <bound method Communication.cmd_vel_flu_callback of <main.Communication instance at 0x7f9c2f80a0>>
Traceback (most recent call last):
File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
cb(msg)
File "multirotor_communication.py", line 112, in cmd_vel_flu_callback
self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
File "multirotor_communication.py", line 146, in hover_state_transition
self.hover()
File "multirotor_communication.py", line 195, in hover
self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
AttributeError: 'NoneType' object has no attribute 'x'

[ERROR] [1658131676.967896, 29.632000]: bad callback: <bound method Communication.cmd_vel_flu_callback of <main.Communication instance at 0x7fa9e09780>>
Traceback (most recent call last):
File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
cb(msg)
File "multirotor_communication.py", line 112, in cmd_vel_flu_callback
self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
File "multirotor_communication.py", line 146, in hover_state_transition
self.hover()
File "multirotor_communication.py", line 195, in hover
self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
AttributeError: 'NoneType' object has no attribute 'x'

[ERROR] [1658131676.972427, 29.632000]: bad callback: <bound method Communication.cmd_vel_flu_callback of <main.Communication instance at 0x7f782bda50>>
Traceback (most recent call last):
File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
cb(msg)
File "multirotor_communication.py", line 112, in cmd_vel_flu_callback
self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
File "multirotor_communication.py", line 146, in hover_state_transition
self.hover()
File "multirotor_communication.py", line 195, in hover
self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
AttributeError: 'NoneType' object has no attribute 'x'

[ERROR] [1658131676.974050, 29.632000]: bad callback: <bound method Communication.cmd_vel_flu_callback of <main.Communication instance at 0x7fb1b680a0>>
Traceback (most recent call last):
File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
cb(msg)
File "multirotor_communication.py", line 112, in cmd_vel_flu_callback
self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
File "multirotor_communication.py", line 146, in hover_state_transition
self.hover()
File "multirotor_communication.py", line 195, in hover
self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
AttributeError: 'NoneType' object has no attribute 'x'

[ERROR] [1658131676.970412, 29.632000]: bad callback: <bound method Communication.cmd_vel_flu_callback of <main.Communication instance at 0x7f8db19c30>>
Traceback (most recent call last):
File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
cb(msg)
File "multirotor_communication.py", line 112, in cmd_vel_flu_callback
self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
File "multirotor_communication.py", line 146, in hover_state_transition
self.hover()
File "multirotor_communication.py", line 195, in hover
self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
AttributeError: 'NoneType' object has no attribute 'x'

[ERROR] [1658131676.976495, 29.632000]: bad callback: <bound method Communication.cmd_vel_flu_callback of <main.Communication instance at 0x7f917cc9b0>>
Traceback (most recent call last):
File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 750, in _invoke_callback
cb(msg)
File "multirotor_communication.py", line 112, in cmd_vel_flu_callback
self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
File "multirotor_communication.py", line 146, in hover_state_transition
self.hover()
File "multirotor_communication.py", line 195, in hover
self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
AttributeError: 'NoneType' object has no attribute 'x'

Object tracking and sensing

I am really new to drones was following the xt-drone manual for ros. It seems the site is not working for yolo installation. I would to use your library with multiple drones for multiple object tracking.After checking it seems the file has been moved to control. Any hint or help is greatly appreciated.

https://www.yuque.com/xtdrone/manual_en/target_detection_tracking

cp -r ~/XTDrone/sensing/object_detection_and_tracking/YOLO/* ~/catkin_ws/src/

make px4_sitl_default gazebo

我运行make px4_sitl_default gazebo出现了以下错误:

CMake Error at CMakeLists.txt:32 (find_package):
By not providing "Findgazebo.cmake" in CMAKE_MODULE_PATH this project has
asked CMake to find a package configuration file provided by "gazebo", but
CMake did not find one.

Could not find a package configuration file provided by "gazebo" with any
of the following names:

gazeboConfig.cmake
gazebo-config.cmake

Add the installation prefix of "gazebo" to CMAKE_PREFIX_PATH or set
"gazebo_DIR" to a directory containing one of the above files. If "gazebo"
provides a separate development package or SDK, be sure it has been
installed.

bashrc问题

GAZEBO_PLUGIN_PATH:/home/j/catkin_ws/src/PX4_Firmware/butld/px4_sttl_default/bu
ild gazebo
GAZEBO_MODEL_PATH :/home/j/catkin ws/src/PX4 Firmware//Tools/sitl_ gazebo/models
LD_LIBRARY_PATH/home/j/catkin_ws/devel/lib:/opt/ros/melodic/lib:/home/j/catkin
ws/src/PX4_Firmware/build/px4_sitl_default/butld_gazebo
这是我弄完bashrc之后,在终端上面出现的,这个可以解决吗?是什么原因呀

三维运动规划

我在运行"rviz -d ego_rviz.rviz"是rviz没有出现点云图
2022-05-10 13-04-29 的屏幕截图
这是运行后的rviz
有解决办法吗

gazebo

Resource not found: The following package was not found in : mavlink_sitl_gazebo
ROS path [0]=/opt/ros/melodic/share/ros
ROS path [1]=/home/j/catkin_ws/src
ROS path [2]=/opt/ros/melodic/share
ROS path [3]=/home/j/catkin_ws/src/PX4_Firmware
ROS path [4]=/home/j/PX4_Firmware/Tools/sitl_gazebo
The traceback for the exception was written to the log file

此为运行roslaunch px4 indoor1.launch的报错指令,请问是啥原因

XTDrone execution problems

Hi, I've followed the https://www.yuque.com/xtdrone/manual_en to install XTDrone with PX4 in a fresh Ubuntu 18.04 install, with ROS Melodic.

I had to change the PX4_Firmware references to the new PX4-Autopilot default name in the copy steps (https://www.yuque.com/xtdrone/manual_en/basic_config_1.11#2qN28).

I didn't download the models.zip as it requires a Yuque account, but the manual says it should download them when executing.

PX4 runs Ok with gazebo when running make px4_sitl gazebo but doesn't compile when I copy the modified gazebo_gimbal_controller_plugin.cpp. It throws the next errors:
`
/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp: In constructor ‘gazebo::GimbalControllerPlugin::GimbalControllerPlugin()’:
/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp:102:9: error: ‘class gazebo::GimbalControllerPlugin’ has no member named ‘lastImuYaw’
this->lastImuYaw = 0;
^~~~~~~~~~

/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp: In member function ‘virtual void gazebo::GimbalControllerPlugin::Init()’:
/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp:397:87: error: ‘ImuCallback’ is not a member of ‘gazebo::GimbalControllerPlugin’
imuSub = node->Subscribe("~/" + model->GetName() + "/imu", &GimbalControllerPlugin::ImuCallback, this);
^~~~~~~~~~~

/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp: At global scope:
/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp:402:42: error: variable or field ‘ImuCallback’ declared void
void GimbalControllerPlugin::ImuCallback(ImuPtr& imu_message)
^~~~~~

/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp:402:42: error: ‘ImuPtr’ was not declared in this scope
/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp:402:50: error: ‘imu_message’ was not declared in this scope
void GimbalControllerPlugin::ImuCallback(ImuPtr& imu_message)
^~~~~~~~~~~

/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp: In member function ‘void gazebo::GimbalControllerPlugin::OnUpdate()’:
/home/foo/PX4-Autopilot/Tools/sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp:477:31: error: ‘class gazebo::GimbalControllerPlugin’ has no member named ‘lastImuYaw’
this->yawCommand += this->lastImuYaw;
^~~~~~~~~~

At global scope:
cc1plus: warning: unrecognized command line option ‘-Wno-address-of-packed-member’
ninja: build stopped: subcommand failed.

FAILED: external/Stamp/sitl_gazebo/sitl_gazebo-build

cd /home/foo/PX4-Autopilot/build/px4_sitl_default/build_gazebo && /usr/bin/cmake --build /home/foo/PX4-Autopilot/build/px4_sitl_default/build_gazebo -- -j2

ninja: build stopped: subcommand failed.

Makefile:217: recipe for target 'px4_sitl_default' failed

make: *** [px4_sitl_default] Error 1
`

Due to this error I restore the original file and try to execute the custom XTDrone launch files, but I get the following errors.
roslaunch px4 indoor1.launch

...

Warning [parser.cc:950] XML Element[contact], child of element[collision] not defined in SDF. Ignoring[contact]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.

Warning [parser.cc:950] XML Element[bounce], child of element[collision] not defined in SDF. Ignoring[bounce]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.

Warning [parser.cc:950] XML Element[friction], child of element[collision] not defined in SDF. Ignoring[friction]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.

[ INFO] [1607554328.840287734]: waitForService: Service [/gazebo/set_physics_properties] is now available.

[ INFO] [1607554328.870219292]: Physics dynamic reconfigure ready.

[INFO] [1607554328.885633, 0.000000]: Loading model XML from file /home/foo/PX4-Autopilot/Tools/sitl_gazebo/models/iris_stereo_camera/iris_stereo_camera.sdf

[INFO] [1607554328.897723, 0.000000]: Waiting for service /gazebo/spawn_sdf_model

[INFO] [1607554328.902918, 0.000000]: Calling service /gazebo/spawn_sdf_model

[INFO] [1607554328.915104, 1814.801000]: Spawn status: SpawnModel: Entity pushed to spawn queue, but spawn service timed out waiting for entity to appear in simulation under the name iris_0

[ERROR] [1607554328.916445, 1814.801000]: Spawn service failed. Exiting.

Warning [parser.cc:950] XML Element[parent], child of element[sensor] not defined in SDF. Ignoring[parent]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.

[vehicle_spawn_foo_4964_5305119535928211108-5] process has died [pid 5020, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -sdf -file /home/foo/PX4-Autopilot/Tools/sitl_gazebo/models/iris_stereo_camera/iris_stereo_camera.sdf -model iris_0 -x 0 -y 7.5 -z 1 -R 0 -P 0 -Y 0 __name:=vehicle_spawn_foo_4964_5305119535928211108 __log:=/home/foo/.ros/log/29d1f0a8-3a71-11eb-90cf-5254002085db/vehicle_spawn_foo_4964_5305119535928211108-5.log].
log file: /home/foo/.ros/log/29d1f0a8-3a71-11eb-90cf-5254002085db/vehicle_spawn_foo_4964_5305119535928211108-5*.log

[ INFO] [1607554329.433231180, 1814.869000000]: Camera Plugin: The 'robotNamespace' param was empty

[ INFO] [1607554329.433478758, 1814.869000000]: Camera Plugin: The 'robotNamespace' param was empty

[ INFO] [1607554329.435768017, 1814.869000000]: Camera Plugin (ns = iris_0) <tf_prefix_>, set to "iris_0"

[ INFO] [1607554329.436079956, 1814.869000000]: Camera Plugin (ns = iris_0) <tf_prefix_>, set to "iris_0"

[ WARN] [1607554329.443008672, 1814.869000000]: missing , set to default: /iris_0/

[ INFO] [1607554329.443051924, 1814.869000000]: set to: /iris_0/imu_gazebo

[ INFO] [1607554329.443063386, 1814.869000000]: set to: imu_link_stereo

[ INFO] [1607554329.443088563, 1814.869000000]: set to: 500

[ INFO] [1607554329.443102359, 1814.869000000]: set to: 0

[ INFO] [1607554329.443123179, 1814.869000000]: set to: 0 0 0

[ INFO] [1607554329.443149619, 1814.869000000]: set to: 0 -0 0

Segmentation fault (core dumped)

[gazebo-3] process has died [pid 4994, exit code 139, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -e ode /home/foo/PX4-Autopilot/Tools/sitl_gazebo/worlds/indoor1.world __name:=gazebo __log:=/home/foo/.ros/log/29d1f0a8-3a71-11eb-90cf-5254002085db/gazebo-3.log].
log file: /home/foo/.ros/log/29d1f0a8-3a71-11eb-90cf-5254002085db/gazebo-3*.log
`

I would like to know if you have any info that can help me solve this errors, thanks!

Could not get initial transform from base to laser frame, "iris_0/laser"

Hello, I tried to run a tutorial, "2D Laser SLAM Simulation" with PX4 firmware v1.11.0-beta1. "roslaunch px4 indoor3.launch" has been executed followed by "roslaunch laser_scan_matcher matcher.launch" in another terminal. I got this error message.

[ WARN] [1589863460.597277470, 2451.336000000]: Skipping scan
[ WARN] [1589863461.607689665, 2452.344000000]: Could not get initial transform from base to laser frame, "iris_0/laser" passed to lookupTransform argument source_frame does not exist.

Nothing appeared in rviz (no expected result as a picture in the tutorial). LaserScan shown status error as "For frame [iris_0/laser]: Frame [iris_0/laser] does not exist" and TF shown warning as "For frame [iris_0/laser]: Frame [iris_0/laser] does not exist".

I really appreciate your help!

gazebo

gazebo的版本是9,运行roslaunch px4 indoor1.launch后,gazebo弹出,但是黑屏,之后意外关闭,终端出现以下信息:
[gazebo_gui-3] process has died [pid 18863, exit code 134, cmd /opt/ros/melodic/lib/gazebo_ros/gzclient __name:=gazebo_gui __log:=/home/j/.ros/log/9080dbae-afe9-11ec-9ce2-08d23e6b72d6/gazebo_gui-3.log].
log file: /home/j/.ros/log/9080dbae-afe9-11ec-9ce2-08d23e6b72d6/gazebo_gui-3*.log

这是啥原因呢

ubuntu20.04起飞显示offboard没有激活是什么原因?

WARN [mc_pos_control] Offboard activation failed with error: Activation Failed
WARN [mc_pos_control] Position-Ctrl activation failed with error: Activation Failed
WARN [mc_pos_control] Altitude-Ctrl activation failed with error: Activation Failed

reset问题

请问xtdrone有提供重设无人机的位姿、速度的rostopic或rosservice或gazebo plugin吗?以及有无碰撞检测功能(就是在和环境障碍物或别的智能体碰撞后能接收到True或者False的rostopic或rosservice或gazebo plugin)

请问如何基于PX4实现3D空间中的避障路径规划?

我是个小白,对建图和路径规划都不太懂,看了不少典型例子.包括PX4的avoidance例子,APM的octomap-planner和ETHZ团队的voxblox-ros等等,还看了用于路径规划的fast-planner和mpl_ros,请问能基于你这个仿真器平台做PX4的视觉自主避障开发么?

ubuntu20.04 make px4_sitl gazebo报错

sitl_gazebo/src/gazebo_gimbal_controller_plugin.cpp:633:11: error: ‘class gazebo::GimbalControllerPlugin’ has no member named ‘yawPub’; did you mean ‘yawPid’?
633 | this->yawPub->Publish(m);
| ^~~~~~
| yawPid
ninja: build stopped: subcommand failed.
FAILED: external/Stamp/sitl_gazebo/sitl_gazebo-build /home/chc/PX4-Autopilot/build/px4_sitl_default/external/Stamp/sitl_gazebo/sitl_gazebo-build
cd /home/chc/PX4-Autopilot/build/px4_sitl_default/build_gazebo && /usr/bin/cmake --build /home/chc/PX4-Autopilot/build/px4_sitl_default/build_gazebo -- -j 5
ninja: build stopped: subcommand failed.
make: *** [Makefile:235:px4_sitl] 错误 1

为何不更新?

老师您好,我想在最新的px4上使用本项目,看到项目文档还是旧版本的px4, 想问既然没有时间办法维护,为何不直接推送到px4官方?

a problem regarding the connection between mavros and sitl

I got some problems when I run ‘roslaunch px4 mavros_posix_sitl.launch’. It can be executed with no error and turn up the world and iris in gazebo correctly but cannot connect to the QGC.

terminal message under 'roslaunch px4 mavros_posix_sitl.launch'
`quantumy@quantumy:~/catkin_wss/mavros_offboard_ws$ roslaunch px4 mavros_posix_sitl.launch
... logging to /home/quantumy/.ros/log/bd0c116c-e08f-11ec-b423-a1f798d135f7/roslaunch-quantumy-53056.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://quantumy:38523/

SUMMARY

CLEAR PARAMETERS

  • /mavros/

PARAMETERS

  • /gazebo/enable_ros_network: True
  • /mavros/camera/frame_id: base_link
  • /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/horizontal_fov_ratio: 1.0
  • /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/distance_sensor/sonar_1_sub/vertical_fov_ratio: 1.0
  • /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@loca...
  • /mavros/gcs_url:
  • /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/mission/use_mission_item_int: 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: noetic
  • /rosversion: 1.15.14
  • /use_sim_time: True

NODES
/
gazebo (gazebo_ros/gzserver)
gazebo_gui (gazebo_ros/gzclient)
mavros (mavros/mavros_node)
sitl (px4/px4)
vehicle_spawn_quantumy_53056_6905434312799540180 (gazebo_ros/spawn_model)

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

setting /run_id to bd0c116c-e08f-11ec-b423-a1f798d135f7
process[rosout-1]: started with pid [53104]
started core service [/rosout]
process[sitl-2]: started with pid [53112]
INFO [px4] Creating symlink /home/quantumy/PX4-Firmware/ROMFS/px4fmu_common -> /home/quantumy/.ros/etc


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

px4 starting.

INFO [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
process[gazebo-3]: started with pid [53124]
process[gazebo_gui-4]: started with pid [53134]
INFO [param] selected parameter default file eeprom/parameters_10016
[param] parameter file not found, creating eeprom/parameters_10016
process[vehicle_spawn_quantumy_53056_6905434312799540180-5]: started with pid [53145]
SYS_AUTOCONFIG: curr: 0 -> new: 1
process[mavros-6]: started with pid [53151]

  • SYS_AUTOSTART: curr: 0 -> new: 10016
    BAT_N_CELLS: curr: 0 -> new: 3
    CAL_ACC0_ID: curr: 0 -> new: 1311244
    CAL_ACC_PRIME: curr: 0 -> new: 1311244
    CAL_GYRO0_ID: curr: 0 -> new: 2294028
    CAL_GYRO_PRIME: curr: 0 -> new: 2294028
    CAL_MAG0_ID: curr: 0 -> new: 197388
    CAL_MAG_PRIME: curr: 0 -> new: 197388
    COM_DISARM_LAND: curr: 2.0000 -> new: 0.5000
    COM_OBL_ACT: curr: 0 -> new: 2
    COM_RC_IN_MODE: curr: 0 -> new: 1
    EKF2_ANGERR_INIT: curr: 0.1000 -> new: 0.0100
    EKF2_GBIAS_INIT: curr: 0.1000 -> new: 0.0100
    COM_ARM_EKF_AB: curr: 0.0017 -> new: 0.0050
    EKF2_REQ_GPS_H: curr: 10.0000 -> new: 0.5000
    MC_PITCH_P: curr: 6.5000 -> new: 6.0000
    MC_PITCHRATE_P: curr: 0.1500 -> new: 0.2000
    MC_ROLL_P: curr: 6.5000 -> new: 6.0000
    MC_ROLLRATE_P: curr: 0.1500 -> new: 0.2000
    MPC_HOLD_MAX_Z: curr: 0.6000 -> new: 2.0000
    MPC_Z_VEL_I: curr: 0.1000 -> new: 0.1500
    MPC_Z_VEL_P: curr: 0.2000 -> new: 0.6000
    MPC_XY_P: curr: 0.9500 -> new: 0.8000
    MPC_XY_VEL_P: curr: 0.0900 -> new: 0.2000
    MPC_XY_VEL_D: curr: 0.0100 -> new: 0.0160
    MPC_SPOOLUP_TIME: curr: 1.0000 -> new: 0.5000
    [ INFO] [1653966850.341020166]: FCU URL: udp://:14540@localhost:14557
    MPC_TKO_RAMP_T: curr: 3.0000 -> new: 1.0000
    [ INFO] [1653966850.342840015]: udp0: Bind address: 0.0.0.0:14540
    [ INFO] [1653966850.342899179]: udp0: Remote address: 127.0.0.1:14557
    [ INFO] [1653966850.342935618]: GCS bridge disabled
    NAV_ACC_RAD: curr: 10.0000 -> new: 2.0000
    [ INFO] [1653966850.348600155]: Plugin 3dr_radio loaded
    [ INFO] [1653966850.349432139]: Plugin 3dr_radio initialized
    [ INFO] [1653966850.349475830]: Plugin actuator_control loaded
    [ INFO] [1653966850.350786798]: Plugin actuator_control initialized
    NAV_DLL_ACT: curr: 0 -> new: 2
    [ INFO] [1653966850.352957021]: Plugin adsb loaded
    RTL_DESCEND_ALT: curr: 30.0000 -> new: 5.0000
    [ INFO] [1653966850.354103577]: Plugin adsb initialized
    [ INFO] [1653966850.354162008]: Plugin altitude loaded
    [ INFO] [1653966850.354485192]: Plugin altitude initialized
    [ INFO] [1653966850.354513693]: Plugin cam_imu_sync loaded
    [ INFO] [1653966850.354722465]: Plugin cam_imu_sync initialized
    [ INFO] [1653966850.354763295]: Plugin camera loaded
    RTL_LAND_DELAY: curr: -1.0000 -> new: 5.0000
    [ INFO] [1653966850.354948100]: Plugin camera initialized
    [ INFO] [1653966850.354979645]: Plugin command loaded
    RTL_RETURN_ALT: curr: 60.0000 -> new: 30.0000
    SDLOG_MODE: curr: 0 -> new: 1
    [ INFO] [1653966850.356950327]: Plugin command initialized
    [ INFO] [1653966850.356991245]: Plugin companion_process_status loaded
    SDLOG_PROFILE: curr: 3 -> new: 131
    [ INFO] [1653966850.357788103]: Plugin companion_process_status initialized
    [ INFO] [1653966850.357839005]: Plugin debug_value loaded
    SDLOG_DIRS_MAX: curr: 0 -> new: 7
    [ INFO] [1653966850.359462149]: Plugin debug_value initialized
    [ INFO] [1653966850.359478520]: Plugin distance_sensor blacklisted
    [ INFO] [1653966850.359510488]: Plugin esc_status loaded
    [ INFO] [1653966850.359851157]: Plugin esc_status initialized
    [ INFO] [1653966850.359880822]: Plugin esc_telemetry loaded
    [ INFO] [1653966850.360056105]: Plugin esc_telemetry initialized
    [ INFO] [1653966850.360090632]: Plugin fake_gps loaded
    SENS_BOARD_X_OFF: curr: 0.0000 -> new: 0.0000
    SENS_DPRES_OFF: curr: 0.0000 -> new: 0.0010
    TRIG_INTERFACE: curr: 4 -> new: 3
    [ INFO] [1653966850.364821277]: Plugin fake_gps initialized
    [ INFO] [1653966850.364885328]: Plugin ftp loaded
    [ INFO] [1653966850.366922998]: Plugin ftp initialized
    [ INFO] [1653966850.366979150]: Plugin geofence loaded
    [ INFO] [1653966850.367950565]: Plugin geofence initialized
    [ INFO] [1653966850.367996482]: Plugin global_position loaded
  • RTL_DESCEND_ALT: curr: 5.0000 -> new: 10.0000
  • RTL_LAND_DELAY: curr: 5.0000 -> new: 0.0000
    PWM_MAX: curr: 2000 -> new: 1950
    PWM_MIN: curr: 1000 -> new: 1075
    [ INFO] [1653966850.373095886]: Plugin global_position initialized
    [ INFO] [1653966850.373148242]: Plugin gps_input loaded
    GPS_UBX_DYNMODEL: curr: 7 -> new: 6
    [ INFO] [1653966850.373974829]: Plugin gps_input initialized
    [ INFO] [1653966850.374013751]: Plugin gps_rtk loaded
  • SYS_AUTOCONFIG: curr: 1 -> new: 0
    [ INFO] [1653966850.374987886]: Plugin gps_rtk initialized
    [ INFO] [1653966850.375028182]: Plugin gps_status loaded
    [ INFO] [1653966850.375835209]: Plugin gps_status initialized
    [ INFO] [1653966850.375883152]: Plugin hil loaded
    [ INFO] [1653966850.379823756]: Plugin hil initialized
    [ INFO] [1653966850.379916104]: Plugin home_position loaded
    [ INFO] [1653966850.381058920]: Plugin home_position initialized
    [ INFO] [1653966850.381115644]: Plugin imu loaded
    [ INFO] [1653966850.383677275]: Plugin imu initialized
    [ INFO] [1653966850.383791249]: Plugin landing_target loaded
    [ INFO] [1653966850.388423618]: Plugin landing_target initialized
    [ INFO] [1653966850.388495682]: Plugin local_position loaded
    INFO [dataman] Unknown restart, data manager file './dataman' size is 11798680 bytes
    [ INFO] [1653966850.390617936]: Plugin local_position initialized
    [ INFO] [1653966850.390672376]: Plugin log_transfer loaded
    [ INFO] [1653966850.391721735]: Plugin log_transfer initialized
    [ INFO] [1653966850.391765127]: Plugin mag_calibration_status loaded
    INFO [simulator] Waiting for simulator to accept connection on TCP port 4560
    [ INFO] [1653966850.392159800]: Plugin mag_calibration_status initialized
    [ INFO] [1653966850.392220369]: Plugin manual_control loaded
    [ INFO] [1653966850.393133527]: Plugin manual_control initialized
    [ INFO] [1653966850.393176913]: Plugin mocap_pose_estimate loaded
    [ INFO] [1653966850.394357670]: Plugin mocap_pose_estimate initialized
    [ INFO] [1653966850.394397584]: Plugin mount_control loaded
    [ INFO] [1653966850.395617973]: Plugin mount_control initialized
    [ INFO] [1653966850.395666040]: Plugin nav_controller_output loaded
    [ INFO] [1653966850.395849694]: Plugin nav_controller_output initialized
    [ INFO] [1653966850.395883731]: Plugin obstacle_distance loaded
    [ INFO] [1653966850.396724326]: Plugin obstacle_distance initialized
    [ INFO] [1653966850.396760209]: Plugin odom loaded
    [ INFO] [1653966850.398119877]: Plugin odom initialized
    [ INFO] [1653966850.398157302]: Plugin onboard_computer_status loaded
    [ INFO] [1653966850.398879686]: Plugin onboard_computer_status initialized
    [ INFO] [1653966850.398929868]: Plugin param loaded
    [ INFO] [1653966850.399763305]: Plugin param initialized
    [ INFO] [1653966850.399799805]: Plugin play_tune loaded
    [ INFO] [1653966850.400528498]: Plugin play_tune initialized
    [ INFO] [1653966850.400571633]: Plugin px4flow loaded
    [ INFO] [1653966850.402695371]: Plugin px4flow initialized
    [ INFO] [1653966850.402754222]: Plugin rallypoint loaded
    [ INFO] [1653966850.403663731]: Plugin rallypoint initialized
    [ INFO] [1653966850.403677231]: Plugin rangefinder blacklisted
    [ INFO] [1653966850.403714337]: Plugin rc_io loaded
    [ INFO] [1653966850.404808098]: Plugin rc_io initialized
    [ INFO] [1653966850.404821782]: Plugin safety_area blacklisted
    [ INFO] [1653966850.404860525]: Plugin setpoint_accel loaded
    [ INFO] [1653966850.405809979]: Plugin setpoint_accel initialized
    [ INFO] [1653966850.405870719]: Plugin setpoint_attitude loaded
    [ INFO] [1653966850.408724490]: Plugin setpoint_attitude initialized
    [ INFO] [1653966850.408786248]: Plugin setpoint_position loaded
    [ INFO] [1653966850.415494440]: Plugin setpoint_position initialized
    [ INFO] [1653966850.415566214]: Plugin setpoint_raw loaded
    [ INFO] [1653966850.418384636]: Plugin setpoint_raw initialized
    [ INFO] [1653966850.418448077]: Plugin setpoint_trajectory loaded
    [ INFO] [1653966850.419899342]: Plugin setpoint_trajectory initialized
    [ INFO] [1653966850.419951322]: Plugin setpoint_velocity loaded
    [ INFO] [1653966850.421695111]: Plugin setpoint_velocity initialized
    [ INFO] [1653966850.421764978]: Plugin sys_status loaded
    [ INFO] [1653966850.425069361]: Plugin sys_status initialized
    [ INFO] [1653966850.425119072]: Plugin sys_time loaded
    [ INFO] [1653966850.426777468]: TM: Timesync mode: MAVLINK
    [ INFO] [1653966850.426903909]: TM: Not publishing sim time
    [ INFO] [1653966850.427255979]: Plugin sys_time initialized
    [ INFO] [1653966850.427300910]: Plugin terrain loaded
    [ INFO] [1653966850.427478896]: Plugin terrain initialized
    [ INFO] [1653966850.427514222]: Plugin trajectory loaded
    [ INFO] [1653966850.429083471]: Plugin trajectory initialized
    [ INFO] [1653966850.429120056]: Plugin tunnel loaded
    [ INFO] [1653966850.429988986]: Plugin tunnel initialized
    [ INFO] [1653966850.430035908]: Plugin vfr_hud loaded
    [ INFO] [1653966850.430217129]: Plugin vfr_hud initialized
    [ INFO] [1653966850.430227693]: Plugin vibration blacklisted
    [ INFO] [1653966850.430263361]: Plugin vision_pose_estimate loaded
    [ INFO] [1653966850.432541904]: Plugin vision_pose_estimate initialized
    [ INFO] [1653966850.432588509]: Plugin vision_speed_estimate loaded
    [ INFO] [1653966850.433737247]: Plugin vision_speed_estimate initialized
    [ INFO] [1653966850.433780215]: Plugin waypoint loaded
    [ INFO] [1653966850.435227489]: Plugin waypoint initialized
    [ INFO] [1653966850.435243133]: Plugin wheel_odometry blacklisted
    [ INFO] [1653966850.435283713]: Plugin wind_estimation loaded
    [ INFO] [1653966850.435471353]: Plugin wind_estimation initialized
    [ INFO] [1653966850.435526308]: Autostarting mavlink via USB on PX4
    [ INFO] [1653966850.435544578]: Built-in SIMD instructions: SSE, SSE2
    [ INFO] [1653966850.435554349]: Built-in MAVLink package version: 2022.3.3
    [ INFO] [1653966850.435566351]: Known MAVLink dialects: common ardupilotmega ASLUAV AVSSUAS all development icarous matrixpilot paparazzi standard storm32 uAvionix ualberta
    [ INFO] [1653966850.435576599]: MAVROS started. MY ID 1.240, TARGET ID 1.1
    [ INFO] [1653966850.501530477]: Finished loading Gazebo ROS API Plugin.
    [ INFO] [1653966850.502181697]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
    [ INFO] [1653966850.521957967]: Finished loading Gazebo ROS API Plugin.
    [ INFO] [1653966850.522855181]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
    [INFO] [1653966850.555177, 0.000000]: Loading model XML from file /home/quantumy/PX4-Firmware/Tools/sitl_gazebo/models/iris/iris.sdf
    [INFO] [1653966850.557046, 0.000000]: Waiting for service /gazebo/spawn_sdf_model
    [ INFO] [1653966851.435895341]: waitForService: Service [/gazebo/set_physics_properties] is now available.
    [ INFO] [1653966851.448221903, 0.008000000]: Physics dynamic reconfigure ready.
    [INFO] [1653966851.460430, 0.000000]: Calling service /gazebo/spawn_sdf_model
    [INFO] [1653966851.648268, 0.176000]: Spawn status: SpawnModel: Successfully spawned entity
    [vehicle_spawn_quantumy_53056_6905434312799540180-5] process has finished cleanly
    log file: /home/quantumy/.ros/log/bd0c116c-e08f-11ec-b423-a1f798d135f7/vehicle_spawn_quantumy_53056_6905434312799540180-5*.log`

I suppose that I configure the mavros correctly by ‘roslaunch mavros px4.launch fcu_url:=“udp://:[email protected]:14557”’ and I also have the correct source in the ~/.bashrc
source /opt/ros/noetic/setup.bash source ~/catkin_wss/catkin_ws_XTDrone/devel/setup.bash source ~/PX4-Firmware/Tools/setup_gazebo.bash ~/PX4-Firmware ~/PX4-Firmware/build/posix_sitl_default export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Firmware export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Firmware/Tools/sitl_gazebo

I can also execute ‘make px4_sitl_default gazebo’ correctly with QGC auto-connected.

Could you please give some advice? I really appreciate any help you can provide.

Is there any possibility to publish the angular velocity and thrust for quadrotor

Hi Robin,

Thank you for your fantastic work and I wanna verify my algorithm on the XTDrone platform. I've checked the multirotor_communication.py carefully. I suppose that the communication node subscribes to the linear velocity and pose, and publishes the setpoint. Can I control my model via publishing angular velocity and thrust? Could you please give some advice? I appreciate any help you can provide.

运行make px4_sitl_default gazebo 报错,gazebo版本为9

[0/6] Performing configure step for 'sitl_gazebo'
-- install-prefix: /usr/local
-- Using C++17 compiler
-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.71.0/BoostConfig.cmake (found suitable version "1.71.0", minimum required is "1.58") found components: system thread filesystem
CMake Warning (dev) at /usr/local/share/cmake-3.18/Modules/FindPackageHandleStandardArgs.cmake:273 (message):
The package name passed to find_package_handle_standard_args (PkgConfig)
does not match the name of the calling package (gazebo). This can lead to
problems in calling code that expects find_package result variables
(e.g., _FOUND) to follow a certain pattern.
Call Stack (most recent call first):
/usr/local/share/cmake-3.18/Modules/FindPkgConfig.cmake:59 (find_package_handle_standard_args)
/usr/lib/x86_64-linux-gnu/cmake/gazebo/gazebo-config.cmake:30 (include)
CMakeLists.txt:32 (find_package)
This warning is for project developers. Use -Wno-dev to suppress it.

-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.71.0/BoostConfig.cmake (found suitable version "1.71.0", minimum required is "1.40.0") found components: thread system filesystem program_options regex iostreams date_time
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1")
-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.71.0/BoostConfig.cmake (found version "1.71.0")
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "2.3.0")
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
-- Found libzmq , version 4.3.2
-- Checking for module 'uuid'
-- Found uuid, version 2.34.0
CMake Error at CMakeLists.txt:34 (find_program):
Could not find px4 using the following names:

-- Configuring incomplete, errors occurred!
See also "/home/asus/PX4_Firmware/build/px4_sitl_default/build_gazebo/CMakeFiles/CMakeOutput.log".
See also "/home/asus/PX4_Firmware/build/px4_sitl_default/build_gazebo/CMakeFiles/CMakeError.log".
[1/6] Generating ../../logs
FAILED: external/Stamp/sitl_gazebo/sitl_gazebo-configure
cd /home/asus/PX4_Firmware/build/px4_sitl_default/build_gazebo && /usr/local/bin/cmake -DCMAKE_INSTALL_PREFIX=/usr/local -DSEND_VISION_ESTIMATION_DATA=ON -GNinja /home/asus/PX4_Firmware/Tools/sitl_gazebo && /usr/local/bin/cmake -E touch /home/asus/PX4_Firmware/build/px4_sitl_default/external/Stamp/sitl_gazebo/sitl_gazebo-configure
ninja: build stopped: subcommand failed.
make: *** [Makefile:200:px4_sitl_default] 错误 1

不知道怎么设置这个路径

GAZEBO_PLUGIN_PATH :/home/asus/PX4_Firmware/build/px4_sitl_default/build_gazebo
GAZEBO_MODEL_PATH :/home/asus/PX4_Firmware//Tools/sitl_gazebo/models
LD_LIBRARY_PATH /home/asus/catkin_ws/devel/lib:/opt/ros/noetic/lib:/home/asus/PX4_Firmware/build/px4_sitl_default/build_gazebo

Imu values from AirSim

I am trying to replicate this work using Airsim.
I didn't know how to take the imu values from airsim. So, can I use imu from MAVROS instead of Gazebo?

#imu_topic: "/iris_0/imu_gazebo"
imu_topic: "/mavros/imu/data"

多機模擬無法執行任務

當我在 SITL 中運行多輛車時,他們可以武裝但無法開始任務。
當我執行鍵盤控制時也是如此
請問要如何解決

145558494-f2e9b292-a123-44df-9588-563a3156b1e9

(已解决)(ubuntu18.04)按照“仿真平台基础配置”教程编译PX4固件报错。

环境配置均按照“仿真平台基础配置”这篇文章进行的。已经完成的步骤如下:
1、已安装ROS melodic。
2、已安装gazebo,但这一步还未进行“我们对Gazebo的ROS插件进行了修改,因此需要源码编译”。
3、已安装MAVROS。
进行到第4步“PX4配置”时,下载了您在语雀上提供的可以直接编译的固件,当我切换到“~/PX4_Firmware”目录下,执行“make px4_sitl_default gazebo”命令,报错如下
2022-09-14 10-15-52屏幕截图
尝试了执行一下“make clean”和“make distclean”命令之后重新执行“make px4_sitl_default gazebo”命令,仍无效果。

No tf is published

how the tf is published within the sdf format robot? there is no tf between the base_link and other sensors.
1

Rviz not receiving camera data

Screenshot from 2021-05-26 00-36-12

Screenshot from 2021-05-26 00-38-57

I'm working on the Visual Inertial Odometer (VIO) tutorial. Rviz also doesn't receive / vins_estimator / image_track data. How can I solve the problem?

多机仿真出错

RLException: while processing /home/sjtu402/PX4_Tools/Firmware/launch/single_vehicle_spawn_xtd.launch:
Invalid tag: Cannot load command parameter [model_description]: no such command [['xmlstarlet', 'ed', '-d', '//plugin[@name="mavlink_interface"]/mavlink_tcp_port', '-s', '//plugin[@name="mavlink_interface"]', '-t', 'elem', '-n', 'mavlink_tcp_port', '-v', '4560', '/home/sjtu402/PX4_Tools/Firmware/Tools/sitl_gazebo/models/solo_stereo_camera/solo_stereo_camera.sdf']].

Param xml is
The traceback for the exception was written to the log file

老师,请问这种错误怎么解决

你好,我在第一次安装编译PX4时出错,但是Could not find px4 using the following names:,这个错误让我不太能理解

gdutelc@gdutelc:~/PX4_Firmware$ make px4_sitl_default gazebo
-- PX4 version: v1.11.0-beta1
-- PX4 config file: /home/gdutelc/PX4_Firmware/boards/px4/sitl/default.cmake
-- PX4 config: px4_sitl_default
-- PX4 platform: posix
-- PX4 lockstep: enabled
-- cmake build type: RelWithDebInfo
-- The CXX compiler identification is GNU 9.3.0
-- The C compiler identification is GNU 9.3.0
-- The ASM compiler identification is GNU
-- Found assembler: /usr/bin/cc
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Check for working CXX compiler: /usr/bin/c++ - skipped
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Check for working C compiler: /usr/bin/cc - skipped
-- Detecting C compile features
-- Detecting C compile features - done
-- Building for code coverage
-- Found PythonInterp: /usr/bin/python3 (found suitable version "3.8.10", minimum required is "3")
-- build type is RelWithDebInfo
-- PX4 ECL: Very lightweight Estimation & Control Library v1.9.0-rc1-255-g47624a0
-- Configuring done
-- Generating done
-- Build files have been written to: /home/gdutelc/PX4_Firmware/build/px4_sitl_default
[0/740] git submodule src/drivers/gps/devices
[2/740] git submodule src/lib/ecl
[8/740] git submodule mavlink/include/mavlink/v2.0
[9/740] git submodule Tools/sitl_gazebo
[18/740] Performing configure step for 'sitl_gazebo'
-- install-prefix: /usr/local
-- The C compiler identification is GNU 9.3.0
-- The CXX compiler identification is GNU 9.3.0
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Check for working C compiler: /usr/bin/cc - skipped
-- Detecting C compile features
-- Detecting C compile features - done
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Check for working CXX compiler: /usr/bin/c++ - skipped
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Performing Test COMPILER_SUPPORTS_CXX17
-- Performing Test COMPILER_SUPPORTS_CXX17 - Success
-- Performing Test COMPILER_SUPPORTS_CXX14
-- Performing Test COMPILER_SUPPORTS_CXX14 - Success
-- Performing Test COMPILER_SUPPORTS_CXX11
-- Performing Test COMPILER_SUPPORTS_CXX11 - Success
-- Performing Test COMPILER_SUPPORTS_CXX0X
-- Performing Test COMPILER_SUPPORTS_CXX0X - Success
-- Using C++17 compiler
-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.71.0/BoostConfig.cmake (found suitable version "1.71.0", minimum required is "1.58") found components: system thread filesystem
CMake Warning (dev) at /opt/cmake-3.22.0-linux-x86_64/share/cmake-3.22/Modules/FindPackageHandleStandardArgs.cmake:438 (message):
  The package name passed to `find_package_handle_standard_args` (PkgConfig)
  does not match the name of the calling package (gazebo).  This can lead to
  problems in calling code that expects `find_package` result variables
  (e.g., `_FOUND`) to follow a certain pattern.
Call Stack (most recent call first):
  /opt/cmake-3.22.0-linux-x86_64/share/cmake-3.22/Modules/FindPkgConfig.cmake:99 (find_package_handle_standard_args)
  /usr/lib/x86_64-linux-gnu/cmake/gazebo/gazebo-config.cmake:72 (include)
  CMakeLists.txt:32 (find_package)
This warning is for project developers.  Use -Wno-dev to suppress it.

-- Found PkgConfig: /usr/bin/pkg-config (found version "0.29.1")
-- Checking for module 'bullet>=2.82'
--   Found bullet, version 2.88
-- Found ccd: /usr/include (found suitable version "2.0", minimum required is "2.0")
-- Found fcl: /usr/include (found suitable version "0.5.0", minimum required is "0.3.2")
-- Found assimp: /usr/include (found version "5.0.0")
-- Found DART: /usr/include (Required is at least version "6.6") found components: dart
-- Found Boost: /usr/lib/x86_64-linux-gnu/cmake/Boost-1.71.0/BoostConfig.cmake (found suitable version "1.71.0", minimum required is "1.40.0") found components: thread system filesystem program_options regex iostreams date_time
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found version "3.6.1")
-- Looking for ignition-math6 -- found version 6.9.2
-- Searching for dependencies of ignition-math6
-- Looking for OGRE...
-- OGRE_PREFIX_WATCH changed.
-- Checking for module 'OGRE'
--   Found OGRE, version 1.9.0
-- Found Ogre Ghadamon (1.9.0)
-- Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
-- Looking for ignition-math6 -- found version 6.9.2
-- Looking for ignition-transport8 -- found version 8.2.1
-- Searching for dependencies of ignition-transport8
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so;-lpthread (found suitable version "3.6.1", minimum required is "3")
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.3.2
-- Found ZeroMQ: TRUE (Required is at least version "4")
-- Checking for module 'uuid'
--   Found uuid, version 2.34.0
-- Found UUID: TRUE
-- Looking for ignition-msgs5 -- found version 5.8.1
-- Searching for dependencies of ignition-msgs5
-- Looking for ignition-math6 -- found version 6.9.2
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.2.0
-- Looking for ignition-msgs5 -- found version 5.8.1
-- Looking for ignition-common3 -- found version 3.14.0
-- Searching for dependencies of ignition-common3
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Found DL: TRUE
-- Searching for <ignition-common3> component [graphics]
-- Looking for ignition-common3-graphics -- found version 3.14.0
-- Searching for dependencies of ignition-common3-graphics
-- Looking for ignition-math6 -- found version 6.9.2
-- Looking for ignition-fuel_tools4 -- found version 4.4.0
-- Searching for dependencies of ignition-fuel_tools4
-- Found CURL: /usr/lib/x86_64-linux-gnu/libcurl.so (found version "7.68.0")
-- Checking for module 'jsoncpp'
--   Found jsoncpp, version 1.7.4
-- Found JSONCPP: TRUE
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.2.2
-- Found YAML: TRUE
-- Checking for module 'libzip'
--   Found libzip, version 1.5.1
-- Found ZIP: TRUE
-- Looking for ignition-common3 -- found version 3.14.0
-- Looking for ignition-math6 -- found version 6.9.2
-- Looking for ignition-msgs5 -- found version 5.8.1
CMake Error at CMakeLists.txt:34 (find_program):
  Could not find px4 using the following names:


-- Configuring incomplete, errors occurred!
See also "/home/gdutelc/PX4_Firmware/build/px4_sitl_default/build_gazebo/CMakeFiles/CMakeOutput.log".
See also "/home/gdutelc/PX4_Firmware/build/px4_sitl_default/build_gazebo/CMakeFiles/CMakeError.log".
[175/740] Building CXX object msg/CMakeFiles/uorb_msgs.dir/topics_sources/ulog_stream.cpp.o
FAILED: external/Stamp/sitl_gazebo/sitl_gazebo-configure /home/gdutelc/PX4_Firmware/build/px4_sitl_default/external/Stamp/sitl_gazebo/sitl_gazebo-configure
cd /home/gdutelc/PX4_Firmware/build/px4_sitl_default/build_gazebo && /opt/cmake-3.22.0-linux-x86_64/bin/cmake -DCMAKE_INSTALL_PREFIX=/usr/local -DSEND_VISION_ESTIMATION_DATA=ON -GNinja /home/gdutelc/PX4_Firmware/Tools/sitl_gazebo && /opt/cmake-3.22.0-linux-x86_64/bin/cmake -E touch /home/gdutelc/PX4_Firmware/build/px4_sitl_default/external/Stamp/sitl_gazebo/sitl_gazebo-configure
[189/740] Building CXX object msg/CMakeFiles/uorb_msgs.dir/topics_sources/ulog_stream.cpp.o
ninja: build stopped: subcommand failed.
make: *** [Makefile:200:px4_sitl_default] 错误 1

这里显示我遇到个cmake文件不完整的问题,但是并没有告诉我少了什么
以下是我的尝试
从github和gitee下载它
尝试过make clean
ubuntu 20.04
我使用的ros如下:


PARAMETERS
 * /rosdistro: noetic
 * /rosversion: 1.15.9

运行indoor.lunch 文件时出现Parameter IMU_INTEG_RATE not found

[gazebo-2] process has died [pid 3850, exit code 134, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -e ode /home/zdk/PX4_Firmware/Tools/sitl_gazebo/worlds/indoor1.world __name:=gazebo __log:=/home/zdk/.ros/log/01fcf3ec-53b1-11ed-bc97-d8bbc19da8dd/gazebo-2.log].
log file: /home/zdk/.ros/log/01fcf3ec-53b1-11ed-bc97-d8bbc19da8dd/gazebo-2*.log
Aborted (core dumped)
[gazebo_gui-3] process has died [pid 3852, exit code 134, cmd /opt/ros/melodic/lib/gazebo_ros/gzclient __name:=gazebo_gui __log:=/home/zdk/.ros/log/01fcf3ec-53b1-11ed-bc97-d8bbc19da8dd/gazebo_gui-3.log].
log file: /home/zdk/.ros/log/01fcf3ec-53b1-11ed-bc97-d8bbc19da8dd/gazebo_gui-3*.log

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.