Giter Club home page Giter Club logo

generalized-intelligence / gaas Goto Github PK

View Code? Open in Web Editor NEW
1.9K 157.0 439.0 303.16 MB

GAAS is an open-source program designed for fully autonomous VTOL(a.k.a flying cars) and drones. GAAS stands for Generalized Autonomy Aviation System.

Home Page: https://www.gaas.dev

License: BSD 3-Clause "New" or "Revised" License

CMake 3.72% C 0.79% C++ 76.04% Python 7.24% Shell 0.16% MATLAB 0.03% Makefile 0.45% CSS 0.01% Meson 0.01% HTML 0.47% Dockerfile 0.01% JavaScript 7.74% Cuda 3.34%
drone drones autonomous-quadcoptor autonomous flying-car aviation flight-controller flight uav vtol

gaas's Introduction

GAAS: Towards L5 Autonomous Flying Cars, a Robust Framework Extends GAAS with Lidars!

StarforkwatchBSD-3twitter

About GAAS

GAAS is an open-source program designed for fully autonomous VTOL(a.k.a flying cars) and drones. GAAS stands for Generalized Autonomy Aviation System. We hope to accelerate human use of the sky through the full autonomy of flying vehicles. This project started in 2016 as a hobby for two students. 2019 we open-source the project and hope to develop GAAS full time in the long term.

GAAS provides a fully autonomous flight platform based on lidar, HD-map relocalization, path planning, and other modules for aircraft. In contrast to the autopilot technology previously available only for consumer-grade drones, GAAS aims for robust fully autonomous flight for human-carrying, and can be easily combined with national air traffic control. At GAAS you can see many of the automotive-grade(AG) technologies that were previously only available in self-driving cars. The whole framework is coupled loosely so you can customize your own modules and easily add them to GAAS.

Previews:

image

image

image

image

A video has been uploaded to show the whole pipeline. You may need to download this video.

Differences between GAAS deprecated and new GAAS:

We use lidars, as main sensor, rather than vision algorithms.

GAAS deprecated is based on computer vision(CV), but fully vision-algorithms-based framework is not robust enough for autonomous flying.

For flying cars and large cargo drones, vision-based algorithms suffer from:

  1. Lack of robustness, especially at night or over-exposed conditions. When air vehicles are flying at high speed, the localization is not stable enough which may cause severe accidents(vital to large air vehicles).

  2. Computer vision is computationally expensive and does not easily run in real-time on mobile devices.

  3. The neural network-based approach is accident-prone in extreme scenarios, and the failures are not easily reproducible.

These problems are not allowed to occur in manned flight scenarios.

Therefore, the introduction of LIDAR seems to be necessary at present. That's why we make new GAAS from scratch, and refactored all modules in cpp.

Build with:

Tested on OS: Ubuntu 18.04; PX4(for simulation only) 1.8.0.

step<1> Check your network status

wget www.google.com

step<2> tools

(optional) install cuda 10.2 for all gpu-based algorithms, like icp_lidar_localization and the gpu version of ndt_localization.

You may need to upgrade cmake to at least 3.13 for building package icp_lidar_localization.

sudo apt install vim bwm-ng htop tmux git net-tools cmake-gui iotop curl

step<3> docker(for simulation only)

curl -fsSL https://get.docker.com | bash -s docker --mirror Aliyun

sudo usermod -aG docker [your username]

docker pull gaas/mavros-gazebo7-px4

step<4> ros_melodic

./install_ros_melodic.sh

step<5> opencv 3.4.5

sudo apt install cmake-qt-gui

[Download opencv 3.4.5 and unzip]

cd opencv-3.4.5/
mkdir build&&cd build&&cmake-gui ..

[Configure your opencv cmake options in cmake-gui]

make -j4&&sudo make install

step<6> glog

git clone https://github.com/google/glog.git
cd glog
git checkout -b v0.4.0
mkdir build&&cd build
cmake ..
make 
sudo make install

step<7> pcl 1.8.0 build from source

[Download pcl 1.8.0 and unzip]

cd pcl-1.8.0
mkdir build&&cd build&&cmake-gui ..

[Configure your pcl cmake options in cmake-gui]

make -j4
sudo make install

step<8> (optional) upgrade your gazebo for simulation

cd GAAS/simulation
./upgrade_gazebo.sh

Getting Started

To build the project, setup all dependencies, run:

./build_all.sh

To run GAAS_contrib algorithms:

cd algorithms
./run_gaas_contrib_algorithms.sh

Start simulation (or play a rosbag instead):

cd simulation&&./scripts/prepare_simulation.sh

or:

rosbag play --clock [path_to_your_rosbag]

And checkout your L5 flying car demo in simulation environment!

License

GAAS is under BSD 3-Clause License.

Features

  1. Simulation env with 32 lines lidar and stereo cameras.

  2. Spinning lidar mapping and NDT matching localization.

Check out simulation/README.md to get more details of simulation env setup.

Roadmap:

1. Gazebo simulation env construction, including spinning lidars and non-repetitive lidars and stereo cameras.

(1). Livox Horizon + Forward Stereo Camera --Done.

(2). Velodyne HDL-32 + Forward Stereo Camera --Done.

2. Accelerate compiling and deployment of GAAS.

3. Implement some LIDAR (mechanical/solid-state) based algorithms, and implement one key start in the simulation environment.

Checklist:

(1). Lidar Points to Image Projection-- Done.

(2). Euclidean Cluster Extraction. --Done.

(3). Global Coordinate based HD-Map Building. --Done.

(4). NDT Lidar Localization(CPU/Cuda) --Done.

(5). Downsampling Node --Done.

(6). A* Path Planner --Done.

(7). Refactored px4 Offboard Commander --Done.

(8). Dynamic Obstacles Generation and Replanning --Done.

(9). Jetson AGX Xavier Adaptation --Done.

(10). Interactive GUI Target Selector in HD-maps --Done.

(11). Multiple Submaps Switching --TODO

(12). IMU-Preintegration and High-Frequency Localization --Done.

(13). VTOL Mode Switching --TODO.

(14). Decentralized Robust Ground Control Station --TODO.

(15). Generalized Flight Controller State Management --Done.

(16). PX4 State Reporter --Done.

(17). HUD Module --Done.

(18). Cuda-based Multiple Lidar Pointclouds ICP Localization --Done.

(19). Ground Points Removal Preprocessing --Done.

(20). System State Surveillance Service --Done.

(21). HTTP Server on Ground Control Station --TODO.

(22). Multiple Spinning Lidar Support --Done.

(23). Airsim Simulation Env Support --Done.

Current status:

Adding logics for flight stage manager module. Including flight stage transfer service clients(triggered by mission config file) and servers(including localization module, flight control commander module and target navigation module.)

gaas's People

Contributors

alexistm avatar cyanine-gi avatar cyninghou avatar doodle1106 avatar gitter-badger avatar hddgi avatar kenwalger avatar masterpa avatar ninawrong avatar robin-shaun avatar

Stargazers

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

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  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

gaas's Issues

Frame_id should be ROS compatible.

Hi there,

The frames should be according to REP 105.

  • frame.body should be base_link
  • frame.local_enu should be:
    • odom if the position is drifting but continuous
    • map if the position has discrete jumps (more likely if using GPS) but not drifting

def set_pose(self, x=0, y=0, z=2, BODY_OFF_SET_ENU = True):
pose = PoseStamped()
pose.header.stamp = rospy.Time.now()
if BODY_OFF_SET_ENU:
pose.header.frame_id = 'frame.body'
pose.pose.position.x = x
pose.pose.position.y = y
pose.pose.position.z = z
else:
pose.header.frame_id = 'frame.local_enu'
pose.pose.position.x = y
pose.pose.position.y = -x
pose.pose.position.z = z
return pose

No point cloud in rviz

Issue Template

Context

Please provide any relevant information about your setup.

  • Tutorial No.:Tutorial 4
  • Mavros: 0.32.1
  • ROS: Kinetic
  • Gazebo: 7
  • Ubuntu: 16.04
  • System Platform: X86

Expected Behavior

When doing the
图片
I should see point cloud in rviz like
图片

Current Behavior

I can't see any point cloud in rviz.

Screenshots

I just do as the tutorials told, everything I can see in my screen:
图片

Failure Logs

Copy console log and paste it here.
图片
图片

And the 'path_planning.launch' consloe log:
... logging to /home/ubuntu/.ros/log/dbb5e6f4-d824-11e9-8baa-03af469f68e4/roslaunch-cch-38852.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://cch:33805/

SUMMARY

CLEAR PARAMETERS

  • /mavros/

PARAMETERS

  • /mavros/cmd/use_comp_id_system_control: False
  • /mavros/conn/heartbeat_rate: 1.0
  • /mavros/conn/system_time_rate: 1.0
  • /mavros/conn/timeout: 10.0
  • /mavros/conn/timesync_rate: 10.0
  • /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
  • /mavros/distance_sensor/hrlv_ez4_pub/id: 0
  • /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
  • /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
  • /mavros/distance_sensor/laser_1_sub/id: 3
  • /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
  • /mavros/distance_sensor/laser_1_sub/subscriber: True
  • /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
  • /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
  • /mavros/distance_sensor/lidarlite_pub/id: 1
  • /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
  • /mavros/distance_sensor/lidarlite_pub/send_tf: True
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
  • /mavros/distance_sensor/sonar_1_sub/id: 2
  • /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
  • /mavros/distance_sensor/sonar_1_sub/subscriber: True
  • /mavros/fake_gps/eph: 2.0
  • /mavros/fake_gps/epv: 2.0
  • /mavros/fake_gps/fix_type: 3
  • /mavros/fake_gps/geo_origin/alt: 408.0
  • /mavros/fake_gps/geo_origin/lat: 47.3667
  • /mavros/fake_gps/geo_origin/lon: 8.55
  • /mavros/fake_gps/gps_rate: 5.0
  • /mavros/fake_gps/mocap_transform: True
  • /mavros/fake_gps/satellites_visible: 5
  • /mavros/fake_gps/tf/child_frame_id: fix
  • /mavros/fake_gps/tf/frame_id: map
  • /mavros/fake_gps/tf/listen: False
  • /mavros/fake_gps/tf/rate_limit: 10.0
  • /mavros/fake_gps/tf/send: False
  • /mavros/fake_gps/use_mocap: True
  • /mavros/fake_gps/use_vision: False
  • /mavros/fcu_protocol: v2.0
  • /mavros/fcu_url: udp://:14540@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/mocap/use_pose: True
  • /mavros/mocap/use_tf: False
  • /mavros/odometry/in/child_frame_id: base_link
  • /mavros/odometry/in/frame_id: odom
  • /mavros/odometry/in/frame_tf/body_frame_orientation: flu
  • /mavros/odometry/in/frame_tf/local_frame: local_origin_ned
  • /mavros/odometry/out/frame_tf/body_frame_orientation: frd
  • /mavros/odometry/out/frame_tf/local_frame: vision_ned
  • /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: map
  • /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: map
  • /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: map
  • /mavros/wheel_odometry/tf/send: True
  • /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: kinetic
  • /rosversion: 1.12.14
  • /use_sim_time: True

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

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

setting /run_id to dbb5e6f4-d824-11e9-8baa-03af469f68e4
process[rosout-1]: started with pid [38875]
started core service [/rosout]
process[sitl-2]: started with pid [38900]
node name: sitl
data path: /home/ubuntu/catkin_ws/src/Firmware
commands file: /home/ubuntu/catkin_ws/src/Firmware/posix-configs/SITL/init/ekf2/iris_stereo_gray_gps
117 WARNING: setRealtimeSched failed (not run as root?)


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

px4 starting.

INFO [dataman] Unknown restart, data manager file 'rootfs/fs/microsd/dataman' size is 11405132 bytes
INFO [simulator] Waiting for initial data on UDP port 14560. Please start the flight simulator to proceed..
process[gazebo-3]: started with pid [38910]
process[gazebo_gui-4]: started with pid [38917]
process[vehicle_spawn_cch_38852_6664878163512917421-5]: started with pid [38922]
process[mavros-6]: started with pid [38923]
[ INFO] [1568598843.987638918]: FCU URL: udp://:14540@localhost:14557
[ INFO] [1568598843.992672714]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1568598843.992828898]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1568598843.993239774]: GCS bridge disabled
[ INFO] [1568598844.015337274]: Plugin 3dr_radio loaded
[ INFO] [1568598844.018908599]: Plugin 3dr_radio initialized
[ INFO] [1568598844.019022312]: Plugin actuator_control loaded
[ INFO] [1568598844.026518085]: Plugin actuator_control initialized
[ INFO] [1568598844.031140907]: Plugin adsb loaded
[ INFO] [1568598844.039618507]: Plugin adsb initialized
[ INFO] [1568598844.039985321]: Plugin altitude loaded
[ INFO] [1568598844.042644586]: Plugin altitude initialized
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1568598844.042969253]: Plugin cam_imu_sync loaded
[ INFO] [1568598844.044721509]: Plugin cam_imu_sync initialized
[ INFO] [1568598844.045088915]: Plugin command loaded
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1568598844.059599101]: Plugin command initialized
[ INFO] [1568598844.059876621]: Plugin companion_process_status loaded
[ INFO] [1568598844.066793883]: Plugin companion_process_status initialized
[ INFO] [1568598844.067099636]: Plugin debug_value loaded
[ INFO] [1568598844.080889271]: Plugin debug_value initialized
[ INFO] [1568598844.080950031]: Plugin distance_sensor blacklisted
[ INFO] [1568598844.081259451]: Plugin fake_gps loaded
[ INFO] [1568598844.119085069]: Plugin fake_gps initialized
[ INFO] [1568598844.119530156]: Plugin ftp loaded
[ INFO] [1568598844.148565741]: Plugin ftp initialized
[ INFO] [1568598844.149137497]: Plugin global_position loaded
[ INFO] [1568598844.151566923]: Finished loading Gazebo ROS API Plugin.
[Msg] Waiting for master.
[ INFO] [1568598844.154826278]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 10.168.40.62
[ INFO] [1568598844.183133103]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1568598844.184356510]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 10.168.40.62
[ INFO] [1568598844.207772142]: Plugin global_position initialized
[ INFO] [1568598844.208091092]: Plugin gps_rtk loaded
[ INFO] [1568598844.212955344]: Plugin gps_rtk initialized
[ INFO] [1568598844.213323227]: Plugin hil loaded
[ INFO] [1568598844.236319172]: Plugin hil initialized
[ INFO] [1568598844.236586869]: Plugin home_position loaded
[ INFO] [1568598844.242752492]: Plugin home_position initialized
[ INFO] [1568598844.243023142]: Plugin imu loaded
[ INFO] [1568598844.263540135]: Plugin imu initialized
[ INFO] [1568598844.263829848]: Plugin landing_target loaded
[ INFO] [1568598844.296158695]: Plugin landing_target initialized
[ INFO] [1568598844.296498495]: Plugin local_position loaded
[ INFO] [1568598844.313564980]: Plugin local_position initialized
[ INFO] [1568598844.313863763]: Plugin log_transfer loaded
SpawnModel script started
[ INFO] [1568598844.321670167]: Plugin log_transfer initialized
[ INFO] [1568598844.321999950]: Plugin manual_control loaded
[ INFO] [1568598844.329766881]: Plugin manual_control initialized
[ INFO] [1568598844.329988251]: Plugin mocap_pose_estimate loaded
[ INFO] [1568598844.340201765]: Plugin mocap_pose_estimate initialized
[ INFO] [1568598844.340493618]: Plugin mount_control loaded
[ INFO] [1568598844.347058849]: Plugin mount_control initialized
[ INFO] [1568598844.347347191]: Plugin obstacle_distance loaded
[ INFO] [1568598844.353895685]: Plugin obstacle_distance initialized
[ INFO] [1568598844.354161630]: Plugin odom loaded
[ INFO] [1568598844.374092314]: Plugin odom initialized
[ INFO] [1568598844.374580554]: Plugin param loaded
[ INFO] [1568598844.382900548]: Plugin param initialized
[ INFO] [1568598844.383190161]: Plugin px4flow loaded
[ INFO] [1568598844.402777885]: Plugin px4flow initialized
[ INFO] [1568598844.402838539]: Plugin rangefinder blacklisted
[ INFO] [1568598844.403207465]: Plugin rc_io loaded
[ INFO] [1568598844.412939839]: Plugin rc_io initialized
[ INFO] [1568598844.413001212]: Plugin safety_area blacklisted
[ INFO] [1568598844.413331959]: Plugin setpoint_accel loaded
[ INFO] [1568598844.422375606]: Plugin setpoint_accel initialized
[ INFO] [1568598844.422877726]: Plugin setpoint_attitude loaded
[ INFO] [1568598844.451979084]: Plugin setpoint_attitude initialized
[ INFO] [1568598844.452352827]: Plugin setpoint_position loaded
[INFO] [1568598844.468882, 0.000000]: Loading model XML from file
[INFO] [1568598844.469312, 0.000000]: Waiting for service /gazebo/spawn_sdf_model
[ INFO] [1568598844.499985112]: Plugin setpoint_position initialized
[ INFO] [1568598844.500362342]: Plugin setpoint_raw loaded
[ INFO] [1568598844.526445304]: Plugin setpoint_raw initialized
[ INFO] [1568598844.526866054]: Plugin setpoint_velocity loaded
[ INFO] [1568598844.543599592]: Plugin setpoint_velocity initialized
[ INFO] [1568598844.544321092]: Plugin sys_status loaded
[ INFO] [1568598844.573699063]: Plugin sys_status initialized
[ INFO] [1568598844.574074923]: Plugin sys_time loaded
[ INFO] [1568598844.589595094]: TM: Timesync mode: MAVLINK
[ INFO] [1568598844.592678894]: Plugin sys_time initialized
[ INFO] [1568598844.592968467]: Plugin trajectory loaded
[ INFO] [1568598844.607917216]: Plugin trajectory initialized
[ INFO] [1568598844.608250794]: Plugin vfr_hud loaded
[ INFO] [1568598844.609871191]: Plugin vfr_hud initialized
[ INFO] [1568598844.609943853]: Plugin vibration blacklisted
[ INFO] [1568598844.610204148]: Plugin vision_pose_estimate loaded
[ INFO] [1568598844.632665475]: Plugin vision_pose_estimate initialized
[ INFO] [1568598844.632955318]: Plugin vision_speed_estimate loaded
[ INFO] [1568598844.644049138]: Plugin vision_speed_estimate initialized
[ INFO] [1568598844.644454285]: Plugin waypoint loaded
[ INFO] [1568598844.656459578]: Plugin waypoint initialized
[ INFO] [1568598844.656550866]: Plugin wheel_odometry blacklisted
[ INFO] [1568598844.656817896]: Plugin wind_estimation loaded
[ INFO] [1568598844.658450833]: Plugin wind_estimation initialized
[ INFO] [1568598844.658546924]: Autostarting mavlink via USB on PX4
[ INFO] [1568598844.658814370]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1568598844.658854758]: Built-in MAVLink package version: 2019.8.8
[ INFO] [1568598844.658900744]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1568598844.658967826]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[INFO] [1568598845.983662, 0.000000]: Calling service /gazebo/spawn_sdf_model
[Wrn] [ColladaLoader.cc:1761] Triangle input semantic: 'TEXCOORD' is currently not supported
[Wrn] [ColladaLoader.cc:1761] Triangle input semantic: 'TEXCOORD' is currently not supported
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/cmake"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/external"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/include"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/models"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/msgs"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/scripts"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/src"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/ubuntu/catkin_ws/src/Firmware/Tools/sitl_gazebo/worlds"
[INFO] [1568598846.170464, 996.334000]: Spawn status: SpawnModel: Entity pushed to spawn queue, but spawn service timed out waiting for entity to appear in simulation under the name iris_stereo_gray_gps
Warning [parser.cc:778] XML Element[child], child of element[sensor] not defined in SDF. Ignoring[child]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:778] 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.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
[vehicle_spawn_cch_38852_6664878163512917421-5] process has finished cleanly
log file: /home/ubuntu/.ros/log/dbb5e6f4-d824-11e9-8baa-03af469f68e4/vehicle_spawn_cch_38852_6664878163512917421-5*.log
[ INFO] [1568598846.517169814, 996.334000000]: Camera Plugin: Using the 'robotNamespace' param: '/'
[ INFO] [1568598846.517419428, 996.334000000]: Camera Plugin: Using the 'robotNamespace' param: '/'
[ INFO] [1568598846.527286665, 996.334000000]: Camera Plugin (ns = /) <tf_prefix_>, set to ""
[ INFO] [1568598846.528149628, 996.334000000]: Camera Plugin (ns = /) <tf_prefix_>, set to ""
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[0] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[1] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[2] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[3] no joint control will be performed for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::propeller_joint] not found for channel[4] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::flap_left_joint] not found for channel[5] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::flap_right_joint] not found for channel[6] no joint control for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[7] no joint control will be performed for this channel.
[Msg] Using MAVLink protocol v2.0
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_gps/motors, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_gps/motor_speed/0, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_gps/motor_speed/1, deleting message. This warning is printed only once.
[ INFO] [1568598846.670110817, 996.356000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1568598846.672344404, 996.358000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1568598846.826615902, 996.508000000]: Physics dynamic reconfigure ready.
[ INFO] [1568598846.836862449, 996.520000000]: Physics dynamic reconfigure ready.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_gps/motor_speed/2, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_gps/motor_speed/3, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_gps/imu, deleting message. This warning is printed only once.
[Err] [Scene.cc:2927] Light [sun] not found. Use topic ~/factory/light to spawn a new light.
[Err] [Scene.cc:2927] Light [sun] not found. Use topic ~/factory/light to spawn a new light.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
[Wrn] [ColladaLoader.cc:1761] Triangle input semantic: 'TEXCOORD' is currently not supported
[Wrn] [ColladaLoader.cc:1761] Triangle input semantic: 'TEXCOORD' is currently not supported
INFO [simulator] Got initial simulation data, running sim..
INFO [pwm_out_sim] MODE_16PWM
INFO [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 14556 remote port 14550
INFO [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14557 remote port 14540
INFO [mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)
INFO [logger] logger started (mode=all)
pxh> INFO [logger] Start file log
INFO [logger] Opened log file: rootfs/fs/microsd/log/2019-09-16/01_54_07.ulg
[ INFO] [1568598847.846489089, 997.506000000]: udp0: Remote address: 127.0.0.1:14557
INFO [mavlink] partner IP: 127.0.0.1
[ INFO] [1568598847.956244315, 997.612000000]: IMU: High resolution IMU detected!
INFO [ecl/EKF] EKF aligned, (pressure height, IMU buf: 22, OBS buf: 14)
[ INFO] [1568598848.751345670, 998.408000000]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1568598848.755860119, 998.414000000]: IMU: High resolution IMU detected!
[ INFO] [1568598848.858601527, 998.516000000]: IMU: Attitude quaternion IMU detected!
[ INFO] [1568598849.755799558, 999.412000000]: VER: 1.1: Capabilities 0x000000000000e4ef
[ INFO] [1568598849.755910592, 999.412000000]: VER: 1.1: Flight software: 010800ff (96443b3cf3e3adae)
[ INFO] [1568598849.755988852, 999.412000000]: VER: 1.1: Middleware software: 010800ff (96443b3cf3e3adae)
[ INFO] [1568598849.756041332, 999.412000000]: VER: 1.1: OS software: 040f00ff (0000000000000000)
[ INFO] [1568598849.756087072, 999.412000000]: VER: 1.1: Board hardware: 00000001
[ INFO] [1568598849.756137488, 999.412000000]: VER: 1.1: VID/PID: 0000:0000
[ INFO] [1568598849.756228992, 999.412000000]: VER: 1.1: UID: 0000000100000002
[ WARN] [1568598849.761542620, 999.418000000]: CMD: Unexpected command 520, result 0
INFO [ecl/EKF] EKF GPS checks passed (WGS-84 origin set)
INFO [ecl/EKF] EKF commencing GPS fusion
[ INFO] [1568598858.773406476, 1008.408000000]: HP: requesting home position
[ INFO] [1568598863.783141454, 1013.408000000]: WP: mission received
[mavros-6] killing on exit
[gazebo_gui-4] killing on exit
[gazebo-3] killing on exit
[sitl-2] killing on exit

Exiting...
pxh> Shutting down
Restoring terminal
[gazebo-3] escalating to SIGTERM
[rosout-1] killing on exit
[master] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

Failed to load plugin libgazebo

When I roslaunch px4 path_planning.launch, errors occur.

[Err] [Plugin.hh:165] Failed to load plugin libgazebo_multirotor_base_plugin.so: libgazebo_multirotor_base_plugin.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_gps_plugin.so: libgazebo_gps_plugin.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_mavlink_interface.so: libgazebo_mavlink_interface.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin libgazebo_imu_plugin.so: libgazebo_imu_plugin.so: cannot open shared object file: No such file or directory

However all about gazebo have been installed.

gazebo7/xenial,now 7.0.0+dfsg-2 amd64 [已安装,自动]
  Open Source Robotics Simulator - Binaries

gazebo7-common/xenial,xenial,now 7.0.0+dfsg-2 all [已安装,自动]
  Open Source Robotics Simulator - Shared files

gazebo7-doc/xenial,xenial 7.0.0+dfsg-2 all
  Open Source Robotics Simulator - Documentation

gazebo7-plugin-base/xenial,now 7.0.0+dfsg-2 amd64 [已安装,自动]
  Open Source Robotics Simulator - base plug-ins

libgazebo7/xenial,now 7.0.0+dfsg-2 amd64 [已安装,自动]
  Open Source Robotics Simulator - shared library

libgazebo7-dev/xenial,now 7.0.0+dfsg-2 amd64 [已安装,自动]
  Open Source Robotics Simulator - Development Files

ros-kinetic-gazebo-dev/xenial,now 2.5.19-1xenial-20190607-165824-0800 amd64 [已安装]
  Provides a cmake config for the default version of Gazebo for the ROS distribution.

ros-kinetic-gazebo-msgs/xenial,now 2.5.19-1xenial-20190608-051945-0800 amd64 [已安装]
  Message and service data structures for interacting with Gazebo from ROS.

ros-kinetic-gazebo-plugins/xenial,now 2.5.19-1xenial-20190608-115731-0800 amd64 [已安装]
  Robot-independent Gazebo plugins for sensors, motors and dynamic reconfigurable components.

ros-kinetic-gazebo-ros/xenial,now 2.5.19-1xenial-20190608-134931-0800 amd64 [已安装]
  Provides ROS plugins that offer message and service publishers for interfacing with Gazebo through ROS.

ros-kinetic-gazebo-ros-control/xenial,now 2.5.19-1xenial-20190608-140610-0800 amd64 [已安装]
  gazebo_ros_control

ros-kinetic-gazebo-ros-pkgs/xenial,now 2.5.19-1xenial-20190608-140634-0800 amd64 [已安装]
  Interface for using ROS with the Gazebo simulator.

[BUG]

Prerequisites

Please answer the following questions for yourself before submitting an issue. YOU MAY DELETE THE PREREQUISITES SECTION.

  • [ v ] I am running the latest version of GAAS
  • [ v ] I checked the Gitbook documentation and found no answer
  • [ v] I checked to make sure that this issue has not already been filed

Issue Template

Context

Please provide any relevant information about your setup.

  • Mavros: [0.18.4]
  • ROS: [Kinetic]
  • Gazebo: [ 7]
  • Ubuntu: [16.04]
  • System Platform: [X86]

I installed the firmware version of px4fmu_v2 1.8.0 on GAAS hardware

And ekf2_aid_mask 8
sys_companion (921600)
ekf2_eva_Noise 0.20
ekf2_evp_Noise 0.20
ekf2_ev_delay 175.0ms
I watched the paramedics

When viewing the mavros/local_position/pose value, Even if you stay still, you lose your position.
Is this a slam problem or a connection speed problem with the pixhawk and tx2 board?

position value x y 0

If this is solved, everything will be solved. help me..

image
image

Weekly Digest (16 June, 2019 - 23 June, 2019)

Here's the Weekly Digest for generalized-intelligence/GAAS:


ISSUES

Last week, no issues were created.


PULL REQUESTS

Last week, no pull requests were created, updated or merged.


COMMITS

Last week there were 14 commits.
🛠️ Merge branch 'master' of https://github.com/generalized-intelligence/GAAS by cyanine-gi
🛠️ added topic config and framework of coordinates_manager;tested okvis and vins seperately;still doing more test for robustness by cyanine-gi
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Update hardware_tut_1.md by ninawrong
🛠️ Update hardware_tut_1.md by ninawrong
🛠️ Create hardware_tut_1.md by ninawrong
🛠️ Update readme.md by ninawrong
🛠️ Update README.MD by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Update README.MD by ninawrong
🛠️ Update README.MD by ninawrong
🛠️ fix a bug, wait 2 sec before node initialized by Doodle1106


CONTRIBUTORS

Last week there were 3 contributors.
👤 cyanine-gi
👤 ninawrong
👤 Doodle1106


STARGAZERS

Last week there were 68 stagazers.
SiuKeungm
wuRDmemory
NicolasHuangDF
AolKleinZ
miaoever
Jeff2Ma
luspock
DusKing1
donghao51
slipingblue
intsilence
ColinWine
mail2li
JohnnyMINIG
PatrickXie17
ostholz
newljs
sosng
skyLiao
qinggeng
cn0xroot
RainGather
litchiate
azazjjyjjy
BG7JAF
garzon
wukezhan
lemondante
S3K1S4KUY4
ACGJoker
josheschulz
Chestergc
stianaske
sudopluto
LuckyZone
MandyMeindersma
luohaoyuan
shineM
buaabai
zhiyue
iBreaker
rrozestw
yeuleh
garyscary
paddyzab
Stell0
simonflyworld
wangzhao765
LeRyc
wilhil
DOITfit
ikimiler
PlutoCYF
onionkingdom
hardin253874
easyphoto
blacklin
yangpeng515
df7c5117
sunziren
BrainforL
skyrusai
WSPeng
Jonexuan
B1lalShah
tankwang87
john-von-seneca
wamburu
You all are the stars! 🌟


RELEASES

Last week there were no releases.


That's all for last week, please 👀 Watch and Star the repository generalized-intelligence/GAAS to receive next weekly updates. 😃

You can also view all Weekly Digests by clicking here.

Your Weekly Digest bot. 📆

ekf2 + vision error

Prerequisites

Please answer the following questions for yourself before submitting an issue. YOU MAY DELETE THE PREREQUISITES SECTION.

  • [ v ] I am running the latest version of GAAS
  • [ v ] I checked the Gitbook documentation and found no answer
  • [ v ] I checked to make sure that this issue has not already been filed
  • [ v ] I Googled/Binged the error messages generated by Ubuntu, Gazebo, and PX4
  • [ v ] I have posted questions regarding Ubuntu, Gazebo, and PX4 in corresponding forums.

Issue Template

Context

  • Tutorial No.:[Tutorial 3]
  • Mavros: [0.18.4]
  • ROS: [Kinetic]
  • Gazebo: [7]
  • Ubuntu: [16.04]
  • System Platform: [X86]

Expected Behavior

When viewing the mavros/local_position/pose value, Even if you stay still, you lose your position.

Is this a slam problem or a connection speed problem with the pixhawk and tx2 board?

At first, it shows the correct position value, but after a while, x y is fixed at zero

There are many of these questions, but all of them have not been solved.

I installed the firmware version of px4fmu_v2 1.8.0

Pixhawk2 + jetson tx2

And ekf2_aid_mask 8 (only vision fusion)
sys_companion (921600)
ekf2_eva_Noise 0.20
ekf2_evp_Noise 0.20
ekf2_ev_delay 50.0ms
ekf2_hgt_mode baro
I watched the paramedics

What is the current behavior?

PARAMETERS

/mavros/cmd/use_comp_id_system_control: False
/mavros/conn/heartbeat_rate: 5.0
/mavros/conn/system_time_rate: 1.0
/mavros/conn/timeout: 5.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: False
/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: False
/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: False
/mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
/mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
/mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
/mavros/distance_sensor/sonar_1_sub/id: 2
/mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
/mavros/distance_sensor/sonar_1_sub/subscriber: False
/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: False
/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: False
/mavros/fake_gps/use_vision: ture
/mavros/fcu_protocol: v2.0
/mavros/fcu_url: /dev/ttyTHS1:921600
/mavros/gcs_url: udp://:14551@192....
/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: False
/mavros/local_position/frame_id: map
/mavros/local_position/tf/child_frame_id: base_link
/mavros/local_position/tf/frame_id: map
/mavros/local_position/tf/send: False
/mavros/local_position/tf/send_fcu: False
/mavros/mission/pull_after_gcs: True
/mavros/mocap/use_pose: False
/mavros/mocap/use_tf: False
/mavros/odometry/in/child_frame_id: base_link
/mavros/odometry/in/frame_id: odom
/mavros/odometry/in/frame_tf/body_frame_orientation: flu
/mavros/odometry/in/frame_tf/local_frame: local_origin_ned
/mavros/odometry/out/frame_tf/body_frame_orientation: frd
/mavros/odometry/out/frame_tf/local_frame: vision_ned
/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: ture
/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: False
/mavros/sys/disable_diag: False
/mavros/sys/min_voltage: 10.0
/mavros/target_component_id: 1
/mavros/target_system_id: 1
/mavros/tdr_radio/low_rssi: 40
/mavros/time/time_ref_source: fcu
/mavros/time/timesync_avg_alpha: 0.6
/mavros/time/timesync_mode: MAVLINK
/mavros/vibration/frame_id: base_link
/mavros/vision_pose/tf/child_frame_id: vision_estimate
/mavros/vision_pose/tf/frame_id: map
/mavros/vision_pose/tf/listen: ture
/mavros/vision_pose/tf/rate_limit: 5.0
/mavros/vision_speed/listen_twist: False
/mavros/vision_speed/twist_cov: False
/mavros/wheel_odometry/child_frame_id: base_link
/mavros/wheel_odometry/count: 2
/mavros/wheel_odometry/frame_id: map
/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: map
/mavros/wheel_odometry/tf/send: True
/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: kinetic
/rosversion: 1.12.14
NODES
/
mavros (mavros/mavros_node)

ROS_MASTER_URI=http://localhost:11311

process[mavros-1]: started with pid [8433]
[ INFO] [1562833794.130340252]: FCU URL: /dev/ttyTHS1:921600
[ INFO] [1562833794.133698132]: serial0: device: /dev/ttyTHS1 @ 921600 bps
[ INFO] [1562833794.144271449]: GCS URL: udp://:[email protected]:14551
[ INFO] [1562833794.144635757]: udp1: Bind address: 0.0.0.0:14551
[ INFO] [1562833794.144775733]: udp1: Remote address: 192.168.0.50:14551
[ INFO] [1562833794.194044201]: Plugin 3dr_radio loaded
[ INFO] [1562833794.207844768]: Plugin 3dr_radio initialized
[ INFO] [1562833794.208029994]: Plugin actuator_control loaded
[ INFO] [1562833794.223757195]: Plugin actuator_control initialized
[ INFO] [1562833794.232957540]: Plugin adsb loaded
[ INFO] [1562833794.248657699]: Plugin adsb initialized
[ INFO] [1562833794.249055833]: Plugin altitude loaded
[ INFO] [1562833794.254389886]: Plugin altitude initialized
[ INFO] [1562833794.254649261]: Plugin cam_imu_sync loaded
[ INFO] [1562833794.257795674]: Plugin cam_imu_sync initialized
[ INFO] [1562833794.258149453]: Plugin command loaded
[ INFO] [1562833794.285167642]: Plugin command initialized
[ INFO] [1562833794.285640244]: Plugin companion_process_status loaded
[ INFO] [1562833794.321122194]: Plugin companion_process_status initialized
[ INFO] [1562833794.321406690]: Plugin debug_value loaded
[ INFO] [1562833794.353694641]: Plugin debug_value initialized
[ INFO] [1562833794.353782134]: Plugin distance_sensor blacklisted
[ INFO] [1562833794.354165803]: Plugin fake_gps loaded
[ERROR] [1562833794.429272875]: No pose source!
[ INFO] [1562833794.429360464]: Plugin fake_gps initialized
[ INFO] [1562833794.429626591]: Plugin ftp loaded
[ INFO] [1562833794.463726161]: Plugin ftp initialized
[ INFO] [1562833794.464293872]: Plugin global_position loaded
[ INFO] [1562833794.567884782]: Plugin global_position initialized
[ INFO] [1562833794.568140700]: Plugin gps_rtk loaded
[ INFO] [1562833794.578616412]: Plugin gps_rtk initialized
[ INFO] [1562833794.578911468]: Plugin hil loaded
[ INFO] [1562833794.653666426]: Plugin hil initialized
[ INFO] [1562833794.654273979]: Plugin home_position loaded
[ INFO] [1562833794.672360477]: Plugin home_position initialized
[ INFO] [1562833794.673046723]: Plugin imu loaded
[ INFO] [1562833794.711945181]: Plugin imu initialized
[ INFO] [1562833794.712511708]: Plugin landing_target loaded
[ INFO] [1562833794.798226180]: Plugin landing_target initialized
[ INFO] [1562833794.798711294]: Plugin local_position loaded
[ INFO] [1562833794.841765021]: Plugin local_position initialized
[ INFO] [1562833794.842046412]: Plugin log_transfer loaded
[ INFO] [1562833794.852325697]: Plugin log_transfer initialized
[ INFO] [1562833794.852625330]: Plugin manual_control loaded
[ INFO] [1562833794.861879150]: Plugin manual_control initialized
[ INFO] [1562833794.862160478]: Plugin mocap_pose_estimate loaded
[ERROR] [1562833794.870789496]: Use one motion capture source.
[ INFO] [1562833794.870888190]: Plugin mocap_pose_estimate initialized
[ INFO] [1562833794.871129899]: Plugin obstacle_distance loaded
[ INFO] [1562833794.887355975]: Plugin obstacle_distance initialized
[ INFO] [1562833794.887645207]: Plugin odom loaded
[ INFO] [1562833794.929173185]: Plugin odom initialized
[ INFO] [1562833794.929706943]: Plugin param loaded
[ INFO] [1562833794.941342974]: Plugin param initialized
[ INFO] [1562833794.941716659]: Plugin px4flow loaded
[ INFO] [1562833794.977737839]: Plugin px4flow initialized
[ INFO] [1562833794.977893719]: Plugin rangefinder blacklisted
[ INFO] [1562833794.978283533]: Plugin rc_io loaded
[ INFO] [1562833795.006652740]: Plugin rc_io initialized
[ INFO] [1562833795.006773035]: Plugin safety_area blacklisted
[ INFO] [1562833795.007158016]: Plugin setpoint_accel loaded
[ INFO] [1562833795.026714420]: Plugin setpoint_accel initialized
[ INFO] [1562833795.027054631]: Plugin setpoint_attitude loaded
[ INFO] [1562833795.086418442]: Plugin setpoint_attitude initialized
[ INFO] [1562833795.086894276]: Plugin setpoint_position loaded
[ INFO] [1562833795.160059230]: Plugin setpoint_position initialized
[ INFO] [1562833795.160500054]: Plugin setpoint_raw loaded
[ INFO] [1562833795.212144848]: Plugin setpoint_raw initialized
[ INFO] [1562833795.212468354]: Plugin setpoint_velocity loaded
[ INFO] [1562833795.241865427]: Plugin setpoint_velocity initialized
[ INFO] [1562833795.242209990]: Plugin sys_status loaded
[ INFO] [1562833795.292462644]: Plugin sys_status initialized
[ INFO] [1562833795.292763780]: Plugin sys_time loaded
[ INFO] [1562833795.317644573]: TM: Timesync mode: MAVLINK
[ INFO] [1562833795.327828750]: Plugin sys_time initialized
[ INFO] [1562833795.328111101]: Plugin trajectory loaded
[ INFO] [1562833795.362818259]: Plugin trajectory initialized
[ INFO] [1562833795.363169830]: Plugin vfr_hud loaded
[ INFO] [1562833795.365557514]: Plugin vfr_hud initialized
[ INFO] [1562833795.365651951]: Plugin vibration blacklisted
[ INFO] [1562833795.365878492]: Plugin vision_pose_estimate loaded
[ INFO] [1562833795.414633270]: Plugin vision_pose_estimate initialized
[ INFO] [1562833795.414931655]: Plugin vision_speed_estimate loaded
[ INFO] [1562833795.433612139]: Plugin vision_speed_estimate initialized
[ INFO] [1562833795.433929340]: Plugin waypoint loaded
[ INFO] [1562833795.454146197]: Plugin waypoint initialized
[ INFO] [1562833795.454255195]: Plugin wheel_odometry blacklisted
[ INFO] [1562833795.454560683]: Plugin wind_estimation loaded
[ INFO] [1562833795.457222782]: Plugin wind_estimation initialized
[ INFO] [1562833795.457461995]: Built-in SIMD instructions: ARM NEON
[ INFO] [1562833795.457549872]: Built-in MAVLink package version: 2019.6.7
[ INFO] [1562833795.457621524]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1562833795.457691416]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1562833795.465020203]: IMU: High resolution IMU detected!
[ INFO] [1562833795.467106622]: IMU: Attitude quaternion IMU detected!
[ERROR] [1562833795.474918156]: ODOM: Ex: The tf tree is invalid because it contains a loop.
Frame local_origin_ned exists with parent local_origin.
Frame fcu_frd exists with parent fcu.
Frame fcu exists with parent fcu_frd.
Frame mynteye_left_frame exists with parent mynteye_link.
Frame mynteye_right_frame exists with parent mynteye_left_frame.
Frame mynteye_left_rect_frame exists with parent mynteye_left_frame.
Frame mynteye_right_rect_frame exists with parent mynteye_right_frame.
Frame mynteye_disparity_frame exists with parent mynteye_left_frame.
Frame mynteye_disparity_norm_frame exists with parent mynteye_disparity_frame.
Frame mynteye_depth_frame exists with parent mynteye_left_frame.
Frame mynteye_points_frame exists with parent mynteye_left_frame.
Frame camera_imu_frame exists with parent mynteye_left_frame.

[ INFO] [1562833796.302940664]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1562833796.311897061]: IMU: High resolution IMU detected!
[ INFO] [1562833796.312096976]: IMU: Attitude quaternion IMU detected!
[ INFO] [1562833797.313536221]: VER: 1.1: Capabilities 0x000000000000e4ef
[ INFO] [1562833797.313649859]: VER: 1.1: Flight software: 01090000 (27ef1899c7000000)
[ INFO] [1562833797.313712550]: VER: 1.1: Middleware software: 01090000 (27ef1899c7000000)
[ INFO] [1562833797.313769450]: VER: 1.1: OS software: 071d00ff (a6f5881ea8513838)
[ INFO] [1562833797.313824173]: VER: 1.1: Board hardware: 00000011
[ INFO] [1562833797.314225603]: VER: 1.1: VID/PID: 26ac:0011
[ INFO] [1562833797.314370027]: VER: 1.1: UID: 3136510c34313630
[ WARN] [1562833797.315030735]: CMD: Unexpected command 520, result 0
[ INFO] [1562833806.303699379]: HP: requesting home position
[ INFO] [1562833811.309390156]: WP: mission received
[ INFO] [1562833816.304163296]: HP: requesting home position
[ INFO] [1562833826.304121341]: HP: requesting home position
[ INFO] [1562833836.303608103]: HP: requesting home position
[ INFO] [1562833846.304631021]: HP: requesting home position
[ INFO] [1562833856.304095432]: HP: requesting home position
[ INFO] [1562833866.303747057]: HP: requesting home position
[ INFO] [1562833876.303636068]: HP: requesting home position
[ INFO] [1562833886.303534918]: HP: requesting home position

Screenshots

Failure Logs

https://logs.px4.io/plot_app?log=3875fcb0-1798-4973-8213-e9a74f420a3e#Nav-Sampling-Regularity-of-Sensor-Data

I'm trying to use gas software in real drone. However, the following problems occur: Did Gaas solve this problem?

[BUG] E06: Basic Object Tracking,When running track_and_move.py

Context

My relevant information about my setup.

  • ROS: [Kinetic]
  • Gazebo: [7.15.0]
  • Ubuntu: [16.04]
  • System Platform: [X86]
  • Python: [2.7.12]

Current Behavior

Autonomous Drone Software E06: Basic Object Tracking

When python track_and_move.py It occurs this question:
Traceback (most recent call last):
File "track_and_move.py", line 134, in
SimpleTrackAndMove(resolution, K,left_topic=left_topic, right_topic=right_topic, object_position_topic=object_position_topic)
TypeError: init() takes at least 4 arguments (6 given)
Screenshot from 2019-09-04 10-17-38
The source code is:
Screenshot from 2019-09-04 10-19-25
Screenshot from 2019-09-04 10-19-40

When I delete commander in def init(),
Screenshot from 2019-09-04 10-21-40
It occurs this question:
Screenshot from 2019-09-04 10-22-17

And if I add commander in the main function,
Screenshot from 2019-09-04 10-24-34

It occurs this question:
Screenshot from 2019-09-04 10-25-11

SLAM Loop-closure

Add loop-closure algorithm to eliminate accumulating errors to the existing feature-based vSLAM through means such as Bags of Words(BoW) and PnP.

bad results report

Issue Template

Context

Please provide any relevant information about your setup.

  • Mavros: [0.18.4]
  • ROS: [ Kinetic]
  • Gazebo: [ 7]
  • Ubuntu: [16.04]
  • System Platform: [X86]

Expected Behavior

I hope the copter could perform better according to the command.

Current Behavior

Takeoff:
Sometimes when the copter takes off, it will fly higher than the expected location and then hovering around the destination. Sometimes, the copter may flies randomly after taking off.
Land:
During the landing process, the copter will keep fly forward. I hope the copter could land just right below or close to the point where it covering.
Flying mission
The copter has not succeeded flying in a square way. The slam will lose when the copter turning 90 degrees and then the copter will fly randomly.
In addition, according to the test tutorial, I have installed all the dependencies including Pangolin EIgen3 g2o PLC and Opencv.
I just want to ask it there results are normal or if I have missed some steps.

Screenshots

These are some screenshots of the trajectories when copters takes off.
2019-05-09 14-34-54屏幕截图

takeoff

2019-05-09 14-35-28屏幕截图
I also simplifies the mission in square.py. I command the copter to fly to the right for 3 meters then turn around for 90 degrees, land finally. This is the results
gpslamline1

Failure Logs

part of the console of slam :********* Tracking frame 2150 **********
I0510 16:05:06.864307 26386 TrackerLK.cpp:110] Tracking frame 1
I0510 16:05:06.879122 26389 BackendSlidingWindowG2O.cpp:133] new good points: 0 in total immature points: 0
I0510 16:05:06.879212 26389 BackendSlidingWindowG2O.cpp:156] Local BA cost time: 9.9e-08
I0510 16:05:06.879249 26389 BackendSlidingWindowG2O.cpp:182] Deleting KF 0
I0510 16:05:06.879266 26389 BackendSlidingWindowG2O.cpp:193] Erase KF in mpKFs
I0510 16:05:06.879516 26389 BackendSlidingWindowG2O.cpp:199] Done
I0510 16:05:06.879671 26389 BackendSlidingWindowG2O.cpp:427] Clean map point done, total bad points 1
I0510 16:05:06.879696 26389 BackendSlidingWindowG2O.cpp:165] Backend KF: 10, map points: 132
I0510 16:05:06.879714 26389 BackendSlidingWindowG2O.cpp:38] Process new KF done.
I0510 16:05:06.902025 26386 Tracker.cpp:1568] Quit iteration in: 10
I0510 16:05:06.904637 26386 Tracker.cpp:1586] Inlier/total=129/129
I0510 16:05:06.904803 26386 Tracker.cpp:1602] Estimated TCW =
0.0767104 00.983975 00.160963 0014.6661
-0.983889 0.0485575 00.172059 004.61203
00.161486 -0.171568 00.971847 0010.8394
000000000 000000000 000000000 000000001
I0510 16:05:06.932163 26386 ORBExtractor.cpp:470] Calling fast single level
I0510 16:05:06.935111 26386 TrackerLK.cpp:541] Detect new feature cost time: 0.00319594
I0510 16:05:06.938956 26386 TrackerLK.cpp:613] new stereo: 0, new Mono: 0, update immature: 0, total features: 129
I0510 16:05:06.939127 26386 TrackerLK.cpp:618] Create map point cost time: 0.00722153
I0510 16:05:06.939270 26386 Tracker.cpp:506] Insert keyframe done.
I0510 16:05:06.939328 26386 TrackerLK.cpp:235] Insert KF cost time: 0.0074259
I0510 16:05:06.939479 26386 TrackerLK.cpp:114] Tracking frame 2
I0510 16:05:06.939540 26386 TrackerLK.cpp:148] Tracking frame 3
I0510 16:05:06.939602 26386 TrackerLK.cpp:153] Tracker position = 1.68634,-12.7308,-13.6894,
vision pose: -14.9427, -10.4848, -4.37022
EstimatedPose : -14.9427, -10.4848, -4.37022
I0510 16:05:06.941656 26389 BackendSlidingWindowG2O.cpp:36] Process new KF
QObject::~QObject: Timers cannot be stopped from another thread

Console of px4 Firmware
... logging to /home/guo/.ros/log/bcb47986-72f9-11e9-9dbb-b0c0902a3964/roslaunch-guo-Lenovo-TianYi-100-14IBD-25090.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/loader.py:409: YAMLLoadWarning: calling yaml.load() without Loader=... is deprecated, as the default Loader is unsafe. Please read https://msg.pyyaml.org/load for full details.
data = yaml.load(text)
started roslaunch server http://guo-Lenovo-TianYi-100-14IBD:43109/

SUMMARY

CLEAR PARAMETERS

  • /mavros/

PARAMETERS

  • /mavros/cmd/use_comp_id_system_control: False
  • /mavros/conn/heartbeat_rate: 1.0
  • /mavros/conn/system_time_rate: 1.0
  • /mavros/conn/timeout: 10.0
  • /mavros/conn/timesync_rate: 10.0
  • /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
  • /mavros/distance_sensor/hrlv_ez4_pub/id: 0
  • /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
  • /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
  • /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
  • /mavros/distance_sensor/laser_1_sub/id: 3
  • /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
  • /mavros/distance_sensor/laser_1_sub/subscriber: True
  • /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
  • /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
  • /mavros/distance_sensor/lidarlite_pub/id: 1
  • /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
  • /mavros/distance_sensor/lidarlite_pub/send_tf: True
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
  • /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
  • /mavros/distance_sensor/sonar_1_sub/id: 2
  • /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
  • /mavros/distance_sensor/sonar_1_sub/subscriber: True
  • /mavros/fake_gps/eph: 2.0
  • /mavros/fake_gps/epv: 2.0
  • /mavros/fake_gps/fix_type: 3
  • /mavros/fake_gps/geo_origin/alt: 408.0
  • /mavros/fake_gps/geo_origin/lat: 47.3667
  • /mavros/fake_gps/geo_origin/lon: 8.55
  • /mavros/fake_gps/gps_rate: 5.0
  • /mavros/fake_gps/mocap_transform: True
  • /mavros/fake_gps/satellites_visible: 5
  • /mavros/fake_gps/tf/child_frame_id: fix
  • /mavros/fake_gps/tf/frame_id: map
  • /mavros/fake_gps/tf/listen: False
  • /mavros/fake_gps/tf/rate_limit: 10.0
  • /mavros/fake_gps/tf/send: False
  • /mavros/fake_gps/use_mocap: True
  • /mavros/fake_gps/use_vision: False
  • /mavros/fcu_protocol: v2.0
  • /mavros/fcu_url: udp://:14540@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.02
  • /mavros/imu/frame_id: base_link
  • /mavros/imu/linear_acceleration_stdev: 0.0003
  • /mavros/imu/magnetic_stdev: 0.0
  • /mavros/imu/orientation_stdev: 1.0
  • /mavros/local_position/frame_id: map
  • /mavros/local_position/tf/child_frame_id: base_link
  • /mavros/local_position/tf/frame_id: map
  • /mavros/local_position/tf/send: False
  • /mavros/local_position/tf/send_fcu: False
  • /mavros/mission/pull_after_gcs: True
  • /mavros/mocap/use_pose: True
  • /mavros/mocap/use_tf: False
  • /mavros/odometry/in/child_frame_id: base_link
  • /mavros/odometry/in/frame_id: odom
  • /mavros/odometry/in/frame_tf/body_frame_orientation: flu
  • /mavros/odometry/in/frame_tf/local_frame: local_origin_ned
  • /mavros/odometry/out/frame_tf/body_frame_orientation: frd
  • /mavros/odometry/out/frame_tf/local_frame: vision_ned
  • /mavros/plugin_blacklist: ['safety_area', '...
  • /mavros/plugin_whitelist: []
  • /mavros/px4flow/frame_id: px4flow
  • /mavros/px4flow/ranger_fov: 6.8
  • /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: map
  • /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: map
  • /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: map
  • /mavros/wheel_odometry/tf/send: True
  • /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: kinetic
  • /rosversion: 1.12.14
  • /use_sim_time: True

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

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

setting /run_id to bcb47986-72f9-11e9-9dbb-b0c0902a3964
process[rosout-1]: started with pid [25113]
started core service [/rosout]
process[sitl-2]: started with pid [25139]
node name: sitl
data path: /home/guo/catkin_ws/src/Firmware
commands file: /home/guo/catkin_ws/src/Firmware/posix-configs/SITL/init/ekf2/iris_stereo_gray_no_gps
65 WARNING: setRealtimeSched failed (not run as root?)


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

px4 starting.

process[gazebo-3]: started with pid [25147]
process[gazebo_gui-4]: started with pid [25154]
process[vehicle_spawn_guo_Lenovo_TianYi_100_14IBD_25090_5892815240772984067-5]: started with pid [25159]
process[mavros-6]: started with pid [25160]
INFO [dataman] Unknown restart, data manager file 'rootfs/fs/microsd/dataman' size is 11405132 bytes
INFO [simulator] Waiting for initial data on UDP port 14560. Please start the flight simulator to proceed..
[ INFO] [1557475256.572810515]: FCU URL: udp://:14540@localhost:14557
[ INFO] [1557475256.577184771]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1557475256.577387877]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1557475256.577844825]: GCS bridge disabled
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1557475256.615857364]: Plugin 3dr_radio loaded
[ INFO] [1557475256.620982244]: Plugin 3dr_radio initialized
[ INFO] [1557475256.621286055]: Plugin actuator_control loaded
[ INFO] [1557475256.630845175]: Plugin actuator_control initialized
[ INFO] [1557475256.647018084]: Plugin adsb loaded
[ INFO] [1557475256.663212473]: Plugin adsb initialized
[ INFO] [1557475256.663638018]: Plugin altitude loaded
[ INFO] [1557475256.676851706]: Plugin altitude initialized
[ INFO] [1557475256.677311405]: Plugin cam_imu_sync loaded
[ INFO] [1557475256.679476151]: Plugin cam_imu_sync initialized
[ INFO] [1557475256.680219681]: Plugin command loaded
[ INFO] [1557475256.706815624]: Plugin command initialized
[ INFO] [1557475256.707275688]: Plugin companion_process_status loaded
[ INFO] [1557475256.720203229]: Plugin companion_process_status initialized
[ INFO] [1557475256.720739406]: Plugin debug_value loaded
[ INFO] [1557475256.739027085]: Plugin debug_value initialized
[ INFO] [1557475256.739270099]: Plugin distance_sensor blacklisted
[ INFO] [1557475256.739733269]: Plugin fake_gps loaded
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1557475256.833805376]: Plugin fake_gps initialized
[ INFO] [1557475256.834341910]: Plugin ftp loaded
[ INFO] [1557475256.848533727]: Finished loading Gazebo ROS API Plugin.
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 134.169.243.94
[ INFO] [1557475256.858632841]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1557475256.881393881]: Plugin ftp initialized
[ INFO] [1557475256.881948055]: Plugin global_position loaded
[ INFO] [1557475256.959289448]: Plugin global_position initialized
[ INFO] [1557475256.959735150]: Plugin gps_rtk loaded
[ INFO] [1557475256.968964349]: Plugin gps_rtk initialized
[ INFO] [1557475256.969449983]: Plugin hil loaded
[ INFO] [1557475257.048677681]: Plugin hil initialized
[ INFO] [1557475257.049249155]: Plugin home_position loaded
[ INFO] [1557475257.073797074]: Plugin home_position initialized
[ INFO] [1557475257.074226634]: Plugin imu loaded
[ INFO] [1557475257.097780951]: Finished loading Gazebo ROS API Plugin.
[Msg] Waiting for master.
[ INFO] [1557475257.104162232]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 134.169.243.94
[ INFO] [1557475257.124159802]: Plugin imu initialized
[ INFO] [1557475257.124574443]: Plugin local_position loaded
[ INFO] [1557475257.152289912]: Plugin local_position initialized
[ INFO] [1557475257.152615234]: Plugin log_transfer loaded
[ INFO] [1557475257.161496706]: Plugin log_transfer initialized
[ INFO] [1557475257.161867984]: Plugin manual_control loaded
[ INFO] [1557475257.170535638]: Plugin manual_control initialized
[ INFO] [1557475257.170840035]: Plugin mocap_pose_estimate loaded
[ INFO] [1557475257.186189051]: Plugin mocap_pose_estimate initialized
[ INFO] [1557475257.186487362]: Plugin obstacle_distance loaded
[ INFO] [1557475257.194409856]: Plugin obstacle_distance initialized
[ INFO] [1557475257.194710930]: Plugin odom loaded
[ INFO] [1557475257.215927630]: Plugin odom initialized
[ INFO] [1557475257.216400522]: Plugin param loaded
[ INFO] [1557475257.225368862]: Plugin param initialized
[ INFO] [1557475257.225649762]: Plugin px4flow loaded
[ INFO] [1557475257.245123543]: Plugin px4flow initialized
[ INFO] [1557475257.245197482]: Plugin rangefinder blacklisted
[ INFO] [1557475257.245599425]: Plugin rc_io loaded
[ INFO] [1557475257.256995418]: Plugin rc_io initialized
[ INFO] [1557475257.257089490]: Plugin safety_area blacklisted
[ INFO] [1557475257.257450869]: Plugin setpoint_accel loaded
[ INFO] [1557475257.269748749]: Plugin setpoint_accel initialized
[ INFO] [1557475257.270240251]: Plugin setpoint_attitude loaded
[ INFO] [1557475257.308590995]: Plugin setpoint_attitude initialized
[ INFO] [1557475257.309042919]: Plugin setpoint_position loaded
[ INFO] [1557475257.366109524]: Plugin setpoint_position initialized
[ INFO] [1557475257.366496509]: Plugin setpoint_raw loaded
[ INFO] [1557475257.409950216]: Plugin setpoint_raw initialized
[ INFO] [1557475257.410378266]: Plugin setpoint_velocity loaded
SpawnModel script started
[ INFO] [1557475257.438146065]: Plugin setpoint_velocity initialized
[ INFO] [1557475257.440797012]: Plugin sys_status loaded
[ INFO] [1557475257.476992263]: Plugin sys_status initialized
[ INFO] [1557475257.477332819]: Plugin sys_time loaded
[ INFO] [1557475257.492696595]: TM: Timesync mode: MAVLINK
[ INFO] [1557475257.498475491]: Plugin sys_time initialized
[ INFO] [1557475257.498997393]: Plugin trajectory loaded
[ INFO] [1557475257.519031800]: Plugin trajectory initialized
[ INFO] [1557475257.519361876]: Plugin vfr_hud loaded
[ INFO] [1557475257.520987916]: Plugin vfr_hud initialized
[ INFO] [1557475257.521171882]: Plugin vibration blacklisted
[ INFO] [1557475257.521475096]: Plugin vision_pose_estimate loaded
[ INFO] [1557475257.548657594]: Plugin vision_pose_estimate initialized
[ INFO] [1557475257.549493553]: Plugin vision_speed_estimate loaded
[ INFO] [1557475257.570823694]: Plugin vision_speed_estimate initialized
[ INFO] [1557475257.571282457]: Plugin waypoint loaded
[ INFO] [1557475257.589921316]: Plugin waypoint initialized
[ INFO] [1557475257.590107046]: Plugin wheel_odometry blacklisted
[ INFO] [1557475257.590427102]: Plugin wind_estimation loaded
[ INFO] [1557475257.597709665]: Plugin wind_estimation initialized
[ INFO] [1557475257.597930283]: Autostarting mavlink via USB on PX4
[ INFO] [1557475257.598377298]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1557475257.598524693]: Built-in MAVLink package version: 2019.4.4
[ INFO] [1557475257.598651588]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1557475257.598767568]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[INFO] [1557475257.655319, 0.000000]: Loading model XML from file
[INFO] [1557475257.655938, 0.000000]: Waiting for service /gazebo/spawn_sdf_model
[ INFO] [1557475257.939922894, 0.026000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[INFO] [1557475257.966327, 0.050000]: Calling service /gazebo/spawn_sdf_model
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/cmake"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/external"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/include"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/models"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/msgs"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/scripts"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/src"
[Err] [InsertModelWidget.cc:298] Missing model.config for model "/home/guo/catkin_ws/src/Firmware/Tools/sitl_gazebo/worlds"
Warning [parser.cc:778] XML Element[child], child of element[sensor] not defined in SDF. Ignoring[child]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:778] 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.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
[INFO] [1557475258.236667, 0.070000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1557475258.277546639, 0.070000000]: Physics dynamic reconfigure ready.
[vehicle_spawn_guo_Lenovo_TianYi_100_14IBD_25090_5892815240772984067-5] process has finished cleanly
log file: /home/guo/.ros/log/bcb47986-72f9-11e9-9dbb-b0c0902a3964/vehicle_spawn_guo_Lenovo_TianYi_100_14IBD_25090_5892815240772984067-5*.log
[ INFO] [1557475258.717826002, 0.070000000]: Camera Plugin: Using the 'robotNamespace' param: '/'
[ INFO] [1557475258.718126496, 0.070000000]: Camera Plugin: Using the 'robotNamespace' param: '/'
[ INFO] [1557475258.727596878, 0.070000000]: Camera Plugin (ns = /) <tf_prefix_>, set to ""
[ INFO] [1557475258.728058946, 0.070000000]: Camera Plugin (ns = /) <tf_prefix_>, set to ""
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[0] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[1] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[2] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[3] no joint control will be performed for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::propeller_joint] not found for channel[4] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::flap_left_joint] not found for channel[5] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:127] joint [zephyr_delta_wing::flap_right_joint] not found for channel[6] no joint control for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:138] <joint_name> not found for channel[7] no joint control will be performed for this channel.
[Msg] Using MAVLink protocol v2.0
[ INFO] [1557475259.062907810, 0.098000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1557475259.163115377, 0.164000000]: Physics dynamic reconfigure ready.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_no_gps/motors, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_no_gps/motor_speed/0, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_no_gps/motor_speed/1, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_no_gps/imu, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_no_gps/motor_speed/2, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_no_gps/motor_speed/3, deleting message. This warning is printed only once.
[Wrn] [msgs.cc:1655] Conversion of sensor type[multicamera] not suppported.
INFO [simulator] Got initial simulation data, running sim..
INFO [pwm_out_sim] MODE_16PWM
INFO [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 14556 remote port 14550
INFO [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14557 remote port 14540
INFO [mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)
pxh> INFO [logger] logger started (mode=all)
INFO [logger] Start file log
INFO [logger] Opened log file: rootfs/fs/microsd/log/2019-05-10/08_01_00.ulg
INFO [mavlink] partner IP: 127.0.0.1
[ INFO] [1557475260.257204303, 1.128000000]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1557475260.378267336, 1.262000000]: IMU: High resolution IMU detected!
INFO [mavlink] partner IP: 127.0.0.1
INFO [ecl/EKF] EKF aligned, (pressure height, IMU buf: 22, OBS buf: 14)
[ INFO] [1557475261.238106135, 2.064000000]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1557475261.248689658, 2.072000000]: IMU: High resolution IMU detected!
[ INFO] [1557475261.361614057, 2.176000000]: IMU: Attitude quaternion IMU detected!
[ INFO] [1557475262.705694238, 3.064000000]: VER: 1.1: Capabilities 0x000000000000e4ef
[ INFO] [1557475262.705787152, 3.064000000]: VER: 1.1: Flight software: 010800ff (96443b3cf3e3adae)
[ INFO] [1557475262.705841238, 3.064000000]: VER: 1.1: Middleware software: 010800ff (96443b3cf3e3adae)
[ INFO] [1557475262.705885628, 3.064000000]: VER: 1.1: OS software: 040f00ff (0000000000000000)
[ INFO] [1557475262.705926492, 3.064000000]: VER: 1.1: Board hardware: 00000001
[ INFO] [1557475262.705969890, 3.064000000]: VER: 1.1: VID/PID: 0000:0000
[ INFO] [1557475262.706015072, 3.064000000]: VER: 1.1: UID: 0000000100000002
[ INFO] [1557475279.586635608, 12.064000000]: HP: requesting home position
[ INFO] [1557475290.977850830, 17.064000000]: WP: mission received
[ INFO] [1557475306.203129558, 22.064000000]: HP: requesting home position
INFO [ecl/EKF] EKF commencing external vision position fusion
[ WARN] [1557475321.681447912, 26.810000000]: CMD: Unexpected command 246, result 0
[ INFO] [1557475336.404410881, 32.064000000]: HP: requesting home position
WARN [commander_tests] Failsafe enabled: no RC
[ WARN] [1557475358.762256937, 39.422000000]: CMD: Unexpected command 176, result 1
[ INFO] [1557475358.778073944, 39.426000000]: WP: reached #0
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris_stereo_gray_no_gps/gazebo/command/motor_speed, deleting message. This warning is printed only once.
[ INFO] [1557475358.839747618, 39.450000000]: WP: reached #0
[ INFO] [1557475359.078308181, 39.530000000]: WP: reached #0

Tutorisas4 question,python Navigator occur errors.

  • Tutorial No.:[ Tutorial 4]
  • Mavros: [0.18.4]
  • ROS: [Kinetic]
  • Gazebo: [7]
  • Ubuntu: [16.04]
  • System Platform: [ X86]

Current Behavior

When I python Navigator.py. It occurs an error. When i use source activate py2.7 to change python version to python2.7,It occurs this problem.

Traceback (most recent call last):
File "Navigator.py", line 422, in
nav = Navigator()
File "Navigator.py", line 89, in init
self.set_status(status.INITIALIZED)
File "Navigator.py", line 401, in set_status
self.STATUS = String(status.name)
AttributeError: 'int' object has no attribute 'name'

But when i use Python 3.7,it ocuurs the different error.
Traceback (most recent call last):
File "Navigator.py", line 22, in
from path_optimization.path_pruning import PathPruning
File "/home/mcx/GAAS/software/Navigator/path_optimization/path_pruning.py", line 4, in
from bresenham3d import Bresenham3D
ModuleNotFoundError: No module named 'bresenham3d'
2019-09-10 15-58-43屏幕截图
2019-09-10 16-05-45屏幕截图

i think this should run in python3 ,because python 2 class xxx(Enum): doen't have name attribution.

ModuleNotFoundError: No module named 'bresenham3d'

  • Tutorial No.:Tutorial 4
  • Mavros: 0.18.4
  • ROS: Kinetic
  • Gazebo: 7
  • Ubuntu: 16.04
  • System Platform: X86
  • python :Python 3.7.3 (default, Mar 27 2019, 22:11:17)
    [GCC 7.3.0] :: Anaconda, Inc. on linux

When python Navigator.py it occurs this problem.
Traceback (most recent call last):
File "Navigator.py", line 24, in
from path_optimization.path_pruning import PathPruning
File "/home/mcx/GAAS/software/Navigator/path_optimization/path_pruning.py", line 3, in
from bresenham3d import Bresenham3D
ModuleNotFoundError: No module named 'bresenham3d'

I have google this problem. But i just find bresenham no bresenham3d. How can i solve this problem? Thanks in advance.

Automatic Landing to Planar Areas

The algorithm can make the drone land on some selected planar areas such as the top of a car, a roof or a balcony. Algorithm required includes plane detection, path planning etc.

Unsupported FCU when started offboard script

After following the tutorial 2 and launching the 'sfm.launch'
file and in new terminal starting 'px4_mavros_run.py'
I get this error [ERROR] [1553594972.501983904, 162.996000000]: MODE: Unsupported FCU in the terminal where i launched the 'sfm.launch' file.

Obstacle_Map calibration mynteye2.yml question

Prerequisites

Please answer the following questions for yourself before submitting an issue. YOU MAY DELETE THE PREREQUISITES SECTION.

  • [v ] I am running the latest version of GAAS
  • [ v] I checked the Gitbook documentation and found no answer
  • [ v] I checked to make sure that this issue has not already been filed
  • I Googled/Binged the error messages generated by Ubuntu, Gazebo, and PX4
  • I have posted questions regarding Ubuntu, Gazebo, and PX4 in corresponding forums.

Issue Template

Context

Please provide any relevant information about your setup.

  • Tutorial No.:[Tutorial 4]
  • Mavros: [ 0.18.4]
  • ROS: [Kinetic]
  • Gazebo: [7]
  • Ubuntu: [16.04]
  • System Platform: [jetson tx2]

Hello

I'm using mynteyes-s camera.

This is the screen that me put into action

1.sh run.sh
2./bin/match_pointcloud_and_slam_pose2

Screenshot from 2019-06-24 08-37-55
you can see very small dense point cloud appeared,

Is this the problem caused by the obstacle_map/calibration/mynteye2.yml file not matching my camera?

Then, tell me how to convert my Yaml file to mynteye2.yml

Screenshot from 2019-06-24 08-48-23
This is my mynteye.yaml file

Screenshot from 2019-06-24 08-50-52

This is obstacle_map/calibration/mynteye2.yml

How to change?

Test & Fix Landing Function

There seems to be some issues with the landing function in ./software/px4_mavros_scripts/1_px4_mavros_offboard_controller/commander.py.

To do:

  1. Test the land function and report if it works well.
  2. Fix if there is an issue.

roslaunch px4 sfm.launch cannot connect

I'm using Ubuntu16.04
Firmware 1.8.2
Gazebo 8.6
I have finished tutorial1 and the vehicle flyt well.
But when I'm running roslaunch px4 sfm.launch. The /mavros/state is not connected.
Could anyone help? Thanks a lot!
The log is as below

... logging to /home/ubuntu/.ros/log/02ffe9d2-644c-11e9-a52f-00117f139124/roslaunch-ubuntu-OptiPlex-960-22008.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://ubuntu-OptiPlex-960:40241/

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/cmd/use_comp_id_system_control: False
 * /mavros/conn/heartbeat_rate: 1.0
 * /mavros/conn/system_time_rate: 1.0
 * /mavros/conn/timeout: 10.0
 * /mavros/conn/timesync_rate: 10.0
 * /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
 * /mavros/distance_sensor/hrlv_ez4_pub/id: 0
 * /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
 * /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/laser_1_sub/id: 3
 * /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/laser_1_sub/subscriber: True
 * /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
 * /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
 * /mavros/distance_sensor/lidarlite_pub/id: 1
 * /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
 * /mavros/distance_sensor/lidarlite_pub/send_tf: True
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/sonar_1_sub/id: 2
 * /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/fake_gps/eph: 2.0
 * /mavros/fake_gps/epv: 2.0
 * /mavros/fake_gps/fix_type: 3
 * /mavros/fake_gps/geo_origin/alt: 408.0
 * /mavros/fake_gps/geo_origin/lat: 47.3667
 * /mavros/fake_gps/geo_origin/lon: 8.55
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/mocap_transform: True
 * /mavros/fake_gps/satellites_visible: 5
 * /mavros/fake_gps/tf/child_frame_id: fix
 * /mavros/fake_gps/tf/frame_id: map
 * /mavros/fake_gps/tf/listen: False
 * /mavros/fake_gps/tf/rate_limit: 10.0
 * /mavros/fake_gps/tf/send: False
 * /mavros/fake_gps/use_mocap: True
 * /mavros/fake_gps/use_vision: False
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: udp://:14540@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.000349065850399
 * /mavros/imu/frame_id: base_link
 * /mavros/imu/linear_acceleration_stdev: 0.0003
 * /mavros/imu/magnetic_stdev: 0.0
 * /mavros/imu/orientation_stdev: 1.0
 * /mavros/local_position/frame_id: map
 * /mavros/local_position/tf/child_frame_id: base_link
 * /mavros/local_position/tf/frame_id: map
 * /mavros/local_position/tf/send: False
 * /mavros/local_position/tf/send_fcu: False
 * /mavros/mission/pull_after_gcs: True
 * /mavros/mocap/use_pose: True
 * /mavros/mocap/use_tf: False
 * /mavros/odometry/in/child_frame_id: base_link
 * /mavros/odometry/in/frame_id: odom
 * /mavros/odometry/in/frame_tf/body_frame_orientation: flu
 * /mavros/odometry/in/frame_tf/local_frame: local_origin_ned
 * /mavros/odometry/out/frame_tf/body_frame_orientation: frd
 * /mavros/odometry/out/frame_tf/local_frame: vision_ned
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682389136
 * /mavros/px4flow/ranger_max_range: 5.0
 * /mavros/px4flow/ranger_min_range: 0.3
 * /mavros/safety_area/p1/x: 1.0
 * /mavros/safety_area/p1/y: 1.0
 * /mavros/safety_area/p1/z: 1.0
 * /mavros/safety_area/p2/x: -1.0
 * /mavros/safety_area/p2/y: -1.0
 * /mavros/safety_area/p2/z: -1.0
 * /mavros/setpoint_accel/send_force: False
 * /mavros/setpoint_attitude/reverse_thrust: False
 * /mavros/setpoint_attitude/tf/child_frame_id: target_attitude
 * /mavros/setpoint_attitude/tf/frame_id: map
 * /mavros/setpoint_attitude/tf/listen: False
 * /mavros/setpoint_attitude/tf/rate_limit: 50.0
 * /mavros/setpoint_attitude/use_quaternion: False
 * /mavros/setpoint_position/mav_frame: LOCAL_NED
 * /mavros/setpoint_position/tf/child_frame_id: target_position
 * /mavros/setpoint_position/tf/frame_id: map
 * /mavros/setpoint_position/tf/listen: False
 * /mavros/setpoint_position/tf/rate_limit: 50.0
 * /mavros/setpoint_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: map
 * /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: map
 * /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: map
 * /mavros/wheel_odometry/tf/send: True
 * /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: kinetic
 * /rosversion: 1.12.14
 * /use_sim_time: True

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

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

setting /run_id to 02ffe9d2-644c-11e9-a52f-00117f139124
process[rosout-1]: started with pid [22031]
started core service [/rosout]
process[sitl-2]: started with pid [22056]
INFO  [px4] Creating symlink /home/ubuntu/src/Firmware/ROMFS/px4fmu_common -> /home/ubuntu/.ros/etc
0 WARNING: setRealtimeSched failed (not run as root?)

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

px4 starting.

INFO  [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
Error: Unknown model 'iris_stereo_rgb_gps'
ERROR [px4] Startup script returned with return value: 256
pxh> process[gazebo-3]: started with pid [22071]
process[gazebo_gui-4]: started with pid [22077]
process[vehicle_spawn_ubuntu_OptiPlex_960_22008_624846013369977176-5]: started with pid [22082]
process[mavros-6]: started with pid [22083]
[ INFO] [1555861325.677890440]: FCU URL: udp://:14540@localhost:14557
[ INFO] [1555861325.680580998]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1555861325.680718819]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1555861325.680862400]: GCS bridge disabled
[ INFO] [1555861325.699145398]: Plugin 3dr_radio loaded
[ INFO] [1555861325.702414397]: Plugin 3dr_radio initialized
[ INFO] [1555861325.702566733]: Plugin actuator_control loaded
[ INFO] [1555861325.709205713]: Plugin actuator_control initialized
[ INFO] [1555861325.713901679]: Plugin adsb loaded
[ INFO] [1555861325.720854050]: Plugin adsb initialized
[ INFO] [1555861325.721073824]: Plugin altitude loaded
[ INFO] [1555861325.723355419]: Plugin altitude initialized
[ INFO] [1555861325.723554940]: Plugin cam_imu_sync loaded
[ INFO] [1555861325.724989550]: Plugin cam_imu_sync initialized
[ INFO] [1555861325.725201904]: Plugin command loaded
[ INFO] [1555861325.737526393]: Plugin command initialized
[ INFO] [1555861325.737744510]: Plugin companion_process_status loaded
[ INFO] [1555861325.743769517]: Plugin companion_process_status initialized
[ INFO] [1555861325.744045119]: Plugin debug_value loaded
[ INFO] [1555861325.757476528]: Plugin debug_value initialized
[ INFO] [1555861325.757546556]: Plugin distance_sensor blacklisted
[ INFO] [1555861325.757733120]: Plugin fake_gps loaded
[ INFO] [1555861325.807450383]: Plugin fake_gps initialized
[ INFO] [1555861325.807726067]: Plugin ftp loaded
[ INFO] [1555861325.833656964]: Plugin ftp initialized
[ INFO] [1555861325.834005743]: Plugin global_position loaded
Gazebo multi-robot simulator, version 8.6.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Wrn] [GuiIface.cc:196] g/gui-plugin is really loading a SystemPlugin. To load a GUI plugin please use --gui-client-plugin 
[ INFO] [1555861325.869551630]: Plugin global_position initialized
[ INFO] [1555861325.869808408]: Plugin gps_rtk loaded
[ INFO] [1555861325.876294487]: Plugin gps_rtk initialized
[ INFO] [1555861325.876614224]: Plugin hil loaded
Gazebo multi-robot simulator, version 8.6.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1555861325.905380652]: Plugin hil initialized
[ INFO] [1555861325.905725013]: Plugin home_position loaded
[ INFO] [1555861325.913355154]: Plugin home_position initialized
[ INFO] [1555861325.913623192]: Plugin imu loaded
[ INFO] [1555861325.929320953]: Plugin imu initialized
[ INFO] [1555861325.929572410]: Plugin local_position loaded
[ INFO] [1555861325.945138292]: Plugin local_position initialized
[ INFO] [1555861325.945374853]: Plugin log_transfer loaded
[ INFO] [1555861325.950422949]: Plugin log_transfer initialized
[ INFO] [1555861325.950771498]: Plugin manual_control loaded
[ INFO] [1555861325.957134880]: Plugin manual_control initialized
[ INFO] [1555861325.957358261]: Plugin mocap_pose_estimate loaded
[ INFO] [1555861325.965482037]: Plugin mocap_pose_estimate initialized
[ INFO] [1555861325.965749062]: Plugin obstacle_distance loaded
[ INFO] [1555861325.972642931]: Plugin obstacle_distance initialized
[ INFO] [1555861325.972913580]: Plugin odom loaded
[ INFO] [1555861325.987224724]: Plugin odom initialized
[ INFO] [1555861325.987588173]: Plugin param loaded
[ INFO] [1555861325.993349733]: Plugin param initialized
[ INFO] [1555861325.993574816]: Plugin px4flow loaded
[ INFO] [1555861326.010359216]: Plugin px4flow initialized
[ INFO] [1555861326.010434615]: Plugin rangefinder blacklisted
[ INFO] [1555861326.010812916]: Plugin rc_io loaded
[ INFO] [1555861326.026459427]: Plugin rc_io initialized
[ INFO] [1555861326.026531699]: Plugin safety_area blacklisted
[ INFO] [1555861326.026754799]: Plugin setpoint_accel loaded
[ INFO] [1555861326.043101042]: Plugin setpoint_accel initialized
[ INFO] [1555861326.043500625]: Plugin setpoint_attitude loaded
[ INFO] [1555861326.050399832]: Finished loading Gazebo ROS API Plugin.
[Msg] Waiting for master.
[ INFO] [1555861326.057128023]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 183.173.87.22
[ INFO] [1555861326.085117591]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1555861326.086268514]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 183.173.87.22
[ INFO] [1555861326.098214187]: Plugin setpoint_attitude initialized
[ INFO] [1555861326.098480538]: Plugin setpoint_position loaded
[ INFO] [1555861326.137945120]: Plugin setpoint_position initialized
[ INFO] [1555861326.138385050]: Plugin setpoint_raw loaded
[ INFO] [1555861326.156155893]: Plugin setpoint_raw initialized
[ INFO] [1555861326.156423255]: Plugin setpoint_velocity loaded
[ INFO] [1555861326.165323152]: Plugin setpoint_velocity initialized
[ INFO] [1555861326.165605555]: Plugin sys_status loaded
[ INFO] [1555861326.180060074]: Plugin sys_status initialized
[ INFO] [1555861326.180321396]: Plugin sys_time loaded
[ INFO] [1555861326.188747519]: TM: Timesync mode: MAVLINK
[ INFO] [1555861326.190451227]: Plugin sys_time initialized
[ INFO] [1555861326.190684388]: Plugin trajectory loaded
[ INFO] [1555861326.199483569]: Plugin trajectory initialized
[ INFO] [1555861326.199717765]: Plugin vfr_hud loaded
[ INFO] [1555861326.201165814]: Plugin vfr_hud initialized
[ INFO] [1555861326.201214276]: Plugin vibration blacklisted
[ INFO] [1555861326.201384192]: Plugin vision_pose_estimate loaded
[ INFO] [1555861326.212981245]: Plugin vision_pose_estimate initialized
[ INFO] [1555861326.213217225]: Plugin vision_speed_estimate loaded
[ INFO] [1555861326.219053012]: Plugin vision_speed_estimate initialized
[ INFO] [1555861326.219287858]: Plugin waypoint loaded
[ INFO] [1555861326.226235777]: Plugin waypoint initialized
[ INFO] [1555861326.226290776]: Plugin wheel_odometry blacklisted
[ INFO] [1555861326.226489054]: Plugin wind_estimation loaded
[ INFO] [1555861326.227393190]: Plugin wind_estimation initialized
[ INFO] [1555861326.227453554]: Autostarting mavlink via USB on PX4
[ INFO] [1555861326.227523453]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1555861326.227558664]: Built-in MAVLink package version: 2019.2.2
[ INFO] [1555861326.227608658]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1555861326.227640768]: MAVROS started. MY ID 1.240, TARGET ID 1.1
SpawnModel script started
[INFO] [1555861326.489421, 0.000000]: Loading model XML from file
[INFO] [1555861326.489848, 0.000000]: Waiting for service /gazebo/spawn_sdf_model
[INFO] [1555861327.397328, 0.000000]: Calling service /gazebo/spawn_sdf_model
[INFO] [1555861327.405088, 149.206000]: Spawn status: SpawnModel: Entity pushed to spawn queue, but spawn service timed out waiting for entity to appear in simulation under the name iris_stereo_rgb_gps
[ INFO] [1555861327.424683308, 149.224000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
Warning [parser.cc:838] XML Element[child], child of element[sensor] not defined in SDF. Ignoring[child]. You may have an incorrect SDF file, or an sdformat version that doesn't support this element.
Warning [parser.cc:838] 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.
[ INFO] [1555861327.542096293, 149.272000000]: Physics dynamic reconfigure ready.
[Wrn] [msgs.cc:1832] Conversion of sensor type[multicamera] not supported.
[vehicle_spawn_ubuntu_OptiPlex_960_22008_624846013369977176-5] process has finished cleanly
log file: /home/ubuntu/.ros/log/02ffe9d2-644c-11e9-a52f-00117f139124/vehicle_spawn_ubuntu_OptiPlex_960_22008_624846013369977176-5*.log
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_ros_multicamera.so: libgazebo_ros_multicamera.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_multirotor_base_plugin.so: libgazebo_multirotor_base_plugin.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_motor_model.so: libgazebo_motor_model.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_gps_plugin.so: libgazebo_gps_plugin.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_mavlink_interface.so: libgazebo_mavlink_interface.so: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:180] Failed to load plugin libgazebo_imu_plugin.so: libgazebo_imu_plugin.so: cannot open shared object file: No such file or directory
[ INFO] [1555861328.079182163, 149.294000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1555861328.149709966, 149.366000000]: Physics dynamic reconfigure ready.
[Wrn] [msgs.cc:1832] Conversion of sensor type[multicamera] not supported.
[Wrn] [msgs.cc:1832] Conversion of sensor type[multicamera] not supported.
[Wrn] [GuiIface.cc:117] void DBusMenuExporterPrivate::addAction(QAction*, int): Already tracking action "&File" under id 56
[Wrn] [GuiIface.cc:117] void DBusMenuExporterPrivate::addAction(QAction*, int): Already tracking action "&Edit" under id 59
[Wrn] [GuiIface.cc:117] void DBusMenuExporterPrivate::addAction(QAction*, int): Already tracking action "&Camera" under id 61
[Wrn] [GuiIface.cc:117] void DBusMenuExporterPrivate::addAction(QAction*, int): Already tracking action "&View" under id 64
[Wrn] [GuiIface.cc:117] void DBusMenuExporterPrivate::addAction(QAction*, int): Already tracking action "&Window" under id 68
[Wrn] [GuiIface.cc:117] void DBusMenuExporterPrivate::addAction(QAction*, int): Already tracking action "&Help" under id 73
[Wrn] [GuiIface.cc:117] QObject::startTimer: Timers cannot be started from another thread
[Wrn] [GuiIface.cc:117] QObject::killTimer: Timers cannot be stopped from another thread
[Wrn] [GuiIface.cc:117] QObject::startTimer: Timers cannot be started from another thread
[Wrn] [GuiIface.cc:117] QObject::killTimer: Timers cannot be stopped from another thread
[Wrn] [GuiIface.cc:117] QObject::startTimer: Timers cannot be started from another thread
[Wrn] [msgs.cc:1832] Conversion of sensor type[multicamera] not supported.

Weekly Digest (9 June, 2019 - 16 June, 2019)

Here's the Weekly Digest for generalized-intelligence/GAAS:


ISSUES

Last week 1 issue was created.
It is closed now.

CLOSED ISSUES

❤️ #40 make posix_sitl_default gazebo-ERROR:recipe for target 'gazebo' failed, by lihan519

NOISY ISSUE

🔈 #40 make posix_sitl_default gazebo-ERROR:recipe for target 'gazebo' failed, by lihan519
It received 1 comments.


PULL REQUESTS

Last week, no pull requests were created, updated or merged.


COMMITS

Last week there were 2 commits.
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong


CONTRIBUTORS

Last week there was 1 contributor.
👤 ninawrong


STARGAZERS

Last week there were 13 stagazers.
karolis1115
aahbirdman
camile666
momocj
lgh5054
laurelkeys
NitinJSanket
StevenCui
vibhu19946
vaughnd
versionercontrol
tiagocpontesp
YimengZhu
You all are the stars! 🌟


RELEASES

Last week there were no releases.


That's all for last week, please 👀 Watch and Star the repository generalized-intelligence/GAAS to receive next weekly updates. 😃

You can also view all Weekly Digests by clicking here.

Your Weekly Digest bot. 📆

Tutorial 4 not publishing Octomap

I get through point cloud display in tutorial 4, but it's not publishing any octomap messages. Rviz sees the message, but nothing gets displayed. If I rostopic echo /occupied_cells_vis_array it says there's no messages and asked if /clock is being published. When I run Navigator, it crashes into the wall, presumably because it doesn't have an octomap? It has shows the point cloud, but I'm guessing it's using the octomap for planning.

website redesigning

are you guys thinking of redesigning https://www.gaas.dev/ (it's already a great website, though ) ?
i got here through reddit, started reading documentation and your tutorials actually makes sense to me :)
i was thinking of integrating https://gaas.gitbook.io/guide/ inside the official website. It would be much cleaner and would make a good starting point to beginner like me.
If you guys are interested, i would like to purpose a much cleaner new official website, along with documentation. (i like what you are doing, and just wanted to be part of this amazing family)

Weekly Digest (2 June, 2019 - 9 June, 2019)

Here's the Weekly Digest for generalized-intelligence/GAAS:


ISSUES

Last week 1 issue was created.
It is closed now.

CLOSED ISSUES

❤️ #38 How to use mavros Publish a XYZ data to put the aircraft in 3DFIX without GPS?, by binbinshare

NOISY ISSUE

🔈 #38 How to use mavros Publish a XYZ data to put the aircraft in 3DFIX without GPS?, by binbinshare
It received 3 comments.


PULL REQUESTS

Last week, no pull requests were created, updated or merged.


COMMITS

Last week there were 6 commits.
🛠️ fix simulation world by Doodle1106
🛠️ Delete obstacle_avoidance.world by Doodle1106
🛠️ Update config.yaml by Doodle1106
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong


CONTRIBUTORS

Last week there were 2 contributors.
👤 Doodle1106
👤 ninawrong


STARGAZERS

Last week there were 21 stagazers.
jin407891080
c00dsummer
50HzVerify
svaichu
jacobculley
patstuff
bp332106
rgreenosborne
wphan
hardKOrr
th3r3isnospoon
CatsAreGods
JustinSaneII
RobotHacker
aoltonen
lgh5054
byj1992
L1ttlewhite
artursg
scottjames
AridTag
You all are the stars! 🌟


RELEASES

Last week there were no releases.


That's all for last week, please 👀 Watch and Star the repository generalized-intelligence/GAAS to receive next weekly updates. 😃

You can also view all Weekly Digests by clicking here.

Your Weekly Digest bot. 📆

Weekly Digest (20 May, 2019 - 27 May, 2019)

Here's the Weekly Digest for generalized-intelligence/GAAS:


ISSUES

Last week 1 issue was created.
It is closed now.

CLOSED ISSUES

❤️ #33 Problem about the compiling of SLAM in Tutorial 3., by pxfdale

NOISY ISSUE

🔈 #33 Problem about the compiling of SLAM in Tutorial 3., by pxfdale
It received 3 comments.


PULL REQUESTS

Last week, no pull requests were created, updated or merged.


COMMITS

Last week there were 16 commits.
🛠️ fix solution selection by Doodle1106
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Update README.MD by Doodle1106
🛠️ add resources for tute 5 by Doodle1106
🛠️ add gif by MasterPa
🛠️ add gif by MasterPa
🛠️ Update README.md by MasterPa
🛠️ Update README.md add gif by MasterPa
🛠️ Update README.md by cyanine-gi
🛠️ fix moving logic by Doodle1106
🛠️ fixed frame error in tutorial 5 by Doodle1106
🛠️ added vertex speed,sliding window;build passed.Will add edge slam prv. by cyanine-gi
🛠️ fix a stupid visualization bug;merged gps and slam position node,seems smooth.TODO:add speed vertex. by cyanine-gi
🛠️ Merge branch 'master' of https://github.com/generalized-intelligence/GAAS by cyanine-gi
🛠️ changed visualizer;added slam position,trying to merge gps and slam. by cyanine-gi


CONTRIBUTORS

Last week there were 4 contributors.
👤 Doodle1106
👤 ninawrong
👤 MasterPa
👤 cyanine-gi


STARGAZERS

Last week there were 16 stagazers.
DeadWisdom
S0leSurvivor
larryswang
mikhail-turicyn
ccll
8669256
Wangwei0223
gkbatchelor
JeffC0227
aesopcode
YYYwky
naveenbiitk
georgeweifly
Kerorohu
luofeixiang
sdjkxhb2016
You all are the stars! 🌟


RELEASES

Last week there were no releases.


That's all for last week, please 👀 Watch and Star the repository generalized-intelligence/GAAS to receive next weekly updates. 😃

You can also view all Weekly Digests by clicking here.

Your Weekly Digest bot. 📆

Multi-stereo-camera Obstacle Detection

Generate a depth map from multiple pairs of stereo cameras for better obstacle avoidance capability. It should be an extension of the existing depth estimation method.

Help with Testing

It will be really helpful if you could help us test GAAS.

Follow the steps below:

English Testing Instruction:
https://gaas.gitbook.io/guide/

Chinese Testing Instruction:
https://gaas.gitbook.io/guide/wu-ren-ji-zi-dong-jia-shi-xi-lie-offboard-kong-zhi-yi-ji-gazebo-fang-zhen

Once you tested GAAS in your environment, you could pull request to GAAS at Testing.md and submit your testing environment and result.

For example Tested Environment:

Memory: 16 GB
Processor: i7-7700HQ
Graphics: GTX 1050
OS: ubuntu 16.04 LTS
Cuda: V9.0.252
2019.1.30 @Doodleshr tested

If you have went through the first tutorial successfully and built everything from source, We would appreciate it if you can provide your hardware setup in a format like below:

Memory:
Processor:
Graphics:
OS:
Cuda:
Date and Name:

Segment fault when running YGZ-SLAM

SLAM Crash

compile GAAS's modified 'YGZ-SLAM' with master branch of PCL, G2O, and DBOW3, the slam crashed, after showing several frames( up to 25th frame some times ) the window disappear and the shell tell me that:

********* Tracking frame 5 **********
I0420 19:26:40.691682 24832 TrackerLK.cpp:110] Tracking frame 1
USING PX4 ATTITUDE INFO!!!
I0420 19:26:40.696871 24832 ORBExtractor.cpp:470] Calling fast single level
I0420 19:26:40.697415 24832 TrackerLK.cpp:554] Detect new feature cost time: 0.0005701
I0420 19:26:40.698292 24832 TrackerLK.cpp:626] new stereo: 0, new Mono: 0, update immature: 0, total features: 80
I0420 19:26:40.698318 24832 TrackerLK.cpp:631] Create map point cost time: 0.00147538
I0420 19:26:40.698329 24832 Tracker.cpp:505] Insert keyframe done.
I0420 19:26:40.698333 24832 TrackerLK.cpp:235] Insert KF cost time: 0.00149248
I0420 19:26:40.698343 24832 TrackerLK.cpp:114] Tracking frame 2
I0420 19:26:40.698351 24832 TrackerLK.cpp:148] Tracking frame 3
I0420 19:26:40.698357 24832 TrackerLK.cpp:153] Tracker position = -1.57783e-06,-2.04626e-06,-7.27003e-06,
vision pose: -2.04625e-06, -7.27004e-06, 1.57778e-06
EstimatedPose : -2.04625e-06, -7.27004e-06, 1.57778e-06
I0420 19:26:40.699643 24833 BackendSlidingWindowG2O.cpp:36] Process new KF
I0420 19:26:40.699885 24833 BackendSlidingWindowG2O.cpp:133] new good points: 0 in total immature points: 27
I0420 19:26:40.699896 24833 BackendSlidingWindowG2O.cpp:156] Local BA cost time: 5.7e-08
I0420 19:26:40.699909 24833 BackendSlidingWindowG2O.cpp:427] Clean map point done, total bad points 0
I0420 19:26:40.699913 24833 BackendSlidingWindowG2O.cpp:165] Backend KF: 6, map points: 80
I0420 19:26:40.699918 24833 BackendSlidingWindowG2O.cpp:38] Process new KF done.
[ INFO] [1555759600.702383595, 89.504000000]: Heading received: 92.612405
[ INFO] [1555759600.723196985, 89.526000000]: Heading received: 92.607102
I0420 19:26:40.730252 24832 TrackerLK.cpp:98]
********* Tracking frame 6 **********
I0420 19:26:40.730317 24832 TrackerLK.cpp:110] Tracking frame 1
USING PX4 ATTITUDE INFO!!!
segment fault(dumped core)

During this time I can see a window with the /gi/simulation output and some colored feature points there(seems It was initialized correctly). Then this window splashed out, and error message show up.

Same error in EurocStereoVO with EurocStereo Dataset

Then I download the dataset for testing your modified YGZ, then crash out too.

BUT EVERYTHING WORKING WELL IN ORIGINAL YGZ

I switch to master Gao's repo and run the ygz the euroc data set, everything looks fine...
But this repo don't support rostopic,,, I feel so sad....

Problem about the compiling of SLAM in Tutorial 3.

I have a problem when I am running " $ sh generate.sh ", it seems that I had some problems in building the dependency of SLAM. ( But I have already followed the steps before...)

The first position error exsists in my log is like this:

-- Checking for module 'openni-dev'
-- No package 'openni-dev' found
-- Found openni: /usr/lib/libOpenNI.so
-- Checking for module 'openni2-dev'
-- No package 'openni2-dev' found
-- Could NOT find OpenNI2 (missing: OPENNI2_LIBRARY OPENNI2_INCLUDE_DIRS)
** WARNING ** io features related to openni2 will be disabled
** WARNING ** io features related to pcap will be disabled
** WARNING ** io features related to png will be disabled
-- The imported target "vtkRenderingPythonTkWidgets" references the file
"/usr/lib/x86_64-linux-gnu/libvtkRenderingPythonTkWidgets.so"
but this file does not exist. Possible reasons include:

  • The file was deleted, renamed, or moved to another location.
  • An install or uninstall procedure did not complete successfully.
  • The installation package was faulty and contained
    "/usr/lib/cmake/vtk-6.2/VTKTargets.cmake"
    but not all the files it references.

-- The imported target "vtk" references the file
"/usr/bin/vtk"
but this file does not exist. Possible reasons include:

  • The file was deleted, renamed, or moved to another location.
  • An install or uninstall procedure did not complete successfully.
  • The installation package was faulty and contained
    "/usr/lib/cmake/vtk-6.2/VTKTargets.cmake"
    but not all the files it references.

And then in this log errors are like this:

/home/pxf/catkin_ws/src/GAAS/software/SLAM/ygz_slam_ros/Thirdparty/DBow3/src/../src/Database.h:31:12: warning: ‘DBoW3::MIN_COMMON_WORDS’ defined but not used [-Wunused-variable]

or like this:

/home/pxf/catkin_ws/src/GAAS/software/SLAM/ygz_slam_ros/backend/src/BackendSlidingWindowG2O.cpp:446:24: error: ‘make_unique’ is not a member of ‘g2o’

What can I do to solve this problem? Or at least know what the real problem is?

Thanks a lot for answering such a basic problem, but I have spend several days on it and still can not find the clues.

Slam Fusion

Implementing a fusion algorithm that combines the output of two or more SLAM pose outputs to one for more accurate and stable vision position estimation.

The algorithm should mainly rely on Bundle Adjustment(G2O, ceres) instead of Filter based methods such as EKF.

Some lapses about the tutorial on the gitbook

genromfs is not a python package

In the section about "environment setting up" of the tutorial part1, when I copy the python modules command, I found that pip can't find 'genromfs'.
And, as far as I know, genromfs can be installed from apt. Hence maybe it should be moved out from pip install xxx\xxx\xxx. But, what if missing this step, maybe some potential fatal wrong arise?

the path of px4_mavros_run.py maybe wrong

cd ~/GAAS/demo/px4_mavros_scripts/1_px4_mavros_offboard_controller should be replaced by .......(your path)/GAAS/demo/tutorial_1/1_px4_mavros_offboard_controller

takeoff failed and "python square.py" failed

Issue Template

Context

Please provide any relevant information about your setup.

  • Tutorial No.:[Tutorial 3]
  • Mavros: [ 0.18.0]
  • ROS: [Kinetic]
  • Gazebo: [7]
  • Ubuntu: [ 16.04]
  • System Platform: [86]

Expected Behavior

The copter takes off and flies in a square way

Current Behavior

Everytime I use python px4_mavros_run.py, the console gives
Px4 Controller Initialized!
Vehicle Took Off Failed!
Then I kill the progress and do python px4_mavros_run.py again. The consoles gives
Px4 Controller Initialized!
Vehicle Took Off!
But the copter does not follow the command. It just fly in a random path.

Screenshots

Failure Logs

Console for takeoff
guo@guo-Lenovo-TianYi-100-14IBD:$ cd GAAS/demo/tutorial_3
guo@guo-Lenovo-TianYi-100-14IBD:
/GAAS/demo/tutorial_3$ python px4_mavros_run.pyPx4 Controller Initialized!
Vehicle Took Off Failed!
^Cguo@guo-Lenovo-TianYi-100-14IBD:~/GAAS/demo/tutorial_3python px4_mavros_run.pyPx4 Controller Initialized!
Vehicle Took Off!
Console for slam
********* Tracking frame 3484 **********
I0508 20:49:34.949198 1792 TrackerLK.cpp:110] Tracking frame 1
W0508 20:49:34.978073 1792 TrackerLK.cpp:397] Track last frame not enough valid matches: 0, I will abort this frame
W0508 20:49:34.978164 1792 TrackerLK.cpp:219] Pure vision tracking failed! Reseting system!!
I0508 20:49:34.978199 1792 TrackerLK.cpp:504] Tracker is reseted
I0508 20:49:34.978232 1792 TrackerLK.cpp:506] Current pose =
000.91478 -0.263826 00.305898 00.969283
00.338744 00.913555 -0.225098 002.85873
-0.220068 00.309536 00.925072 006.18012
000000000 000000000 000000000 000000001
I0508 20:49:34.978381 1792 BackendSlidingWindowG2O.cpp:1716] Backend is reset
I0508 20:49:34.981477 1792 BackendSlidingWindowG2O.cpp:1722] backend reset done.
I0508 20:49:34.981520 1792 TrackerLK.cpp:512] Try init stereo
I0508 20:49:34.981535 1792 ORBExtractor.cpp:470] Calling fast single level
I0508 20:49:34.983662 1792 Tracker.cpp:525] Valid feature is not enough! current:0;min valid num:7
I0508 20:49:34.983932 1792 TrackerLK.cpp:517] Stereo init failed.
I0508 20:49:34.984055 1792 TrackerLK.cpp:114] Tracking frame 2
I0508 20:49:34.984088 1792 TrackerLK.cpp:148] Tracking frame 3
I0508 20:49:34.984108 1792 TrackerLK.cpp:153] Tracker position = 0.969283,2.85873,6.18012,
vision pose: 4.26885, 5.37006, -0.495011
EstimatedPose : 4.26885, 5.37006, -0.495011
[ INFO] [1557319774.984965111, 157.616000000]: Heading received: 135.439447
[ INFO] [1557319774.985343938, 157.616000000]: Heading received: 135.437359
I0508 20:49:35.010515 1792 TrackerLK.cpp:98]

********* Tracking frame 3485 **********
I0508 20:49:35.010596 1792 TrackerLK.cpp:110] Tracking frame 1
^CW0508 20:49:35.081715 1792 TrackerLK.cpp:397] Track last frame not enough valid matches: 0, I will abort this frame
W0508 20:49:35.081845 1792 TrackerLK.cpp:219] Pure vision tracking failed! Reseting system!!
I0508 20:49:35.081892 1792 TrackerLK.cpp:504] Tracker is reseted
I0508 20:49:35.081948 1792 TrackerLK.cpp:506] Current pose =
000.91478 -0.263826 00.305898 00.969283
00.338744 00.913555 -0.225098 002.85873
-0.220068 00.309536 00.925072 006.18012
000000000 000000000 000000000 000000001
I0508 20:49:35.082149 1792 BackendSlidingWindowG2O.cpp:1716] Backend is reset
I0508 20:49:35.085438 1792 BackendSlidingWindowG2O.cpp:1722] backend reset done.
I0508 20:49:35.085839 1792 TrackerLK.cpp:512] Try init stereo
I0508 20:49:35.085901 1792 ORBExtractor.cpp:470] Calling fast single level
I0508 20:49:35.106935 1792 Tracker.cpp:525] Valid feature is not enough! current:0;min valid num:7
I0508 20:49:35.107000 1792 TrackerLK.cpp:517] Stereo init failed.
I0508 20:49:35.107018 1792 TrackerLK.cpp:114] Tracking frame 2
I0508 20:49:35.107030 1792 TrackerLK.cpp:148] Tracking frame 3
I0508 20:49:35.107041 1792 TrackerLK.cpp:153] Tracker position = 0.969283,2.85873,6.18012,
vision pose: 4.26885, 5.37006, -0.495011
EstimatedPose : 4.26885, 5.37006, -0.495011

Warning when compiling YGZ-slam

Please provide any relevant information about your setup.

  • Tutorial No.:Tutorial 3
  • Mavros: 0.18.4
  • ROS: Kinetic
  • Gazebo:7
  • Ubuntu: 16.04
  • System Platform: X86
    *OpenCV :3.3.1

I'm trying to compile the YGZ-slam by "sh generate,sh" and i ran into the warning as shown below. Despite that, i'm still able to compile it successfully. May i know if this warning will affect the performance of the slam.

Warning log:
Could NOT find ensenso (missing: ENSENSO_LIBRARY ENSENSO_INCLUDE_DIR)
** WARNING ** io features related to ensenso will be disabled
-- Could NOT find DAVIDSDK (missing: DAVIDSDK_LIBRARY DAVIDSDK_INCLUDE_DIR)
** WARNING ** io features related to davidSDK will be disabled
-- Could NOT find DSSDK (missing: _DSSDK_LIBRARIES)
** WARNING ** io features related to dssdk will be disabled
** WARNING ** io features related to pcap will be disabled
** WARNING ** io features related to png will be disabled
** WARNING ** io features related to libusb-1.0 will be disabled
-- Could NOT find ensenso (missing: ENSENSO_LIBRARY ENSENSO_INCLUDE_DIR)
** WARNING ** visualization features related to ensenso will be disabled
-- Could NOT find DAVIDSDK (missing: DAVIDSDK_LIBRARY DAVIDSDK_INCLUDE_DIR)
** WARNING ** visualization features related to davidSDK will be disabled
-- Could NOT find DSSDK (missing: _DSSDK_LIBRARIES)
** WARNING ** visualization features related to dssdk will be disabled
-- Could NOT find RSSDK (missing: _RSSDK_LIBRARIES)
** WARNING ** visualization features related to rssdk will be disabled

Weekly Digest (21 July, 2019 - 28 July, 2019)

Here's the Weekly Digest for generalized-intelligence/GAAS:

ISSUES

This week, 3 issues were created. Of these, 2 issues have been closed and 1 issues are still open.

OPEN ISSUES

💚 #47 ResourceNotFoundError: gazebo_ros. Cannot run the first tutorial, by atmadeep

CLOSED ISSUES

❤️ #46 ekf2 + vision error , by lgh5054
❤️ #45 , by weiyaoxing

NOISY ISSUE

The issue most discussed this week has been:
🔈 #47 ResourceNotFoundError: gazebo_ros. Cannot run the first tutorial, by atmadeep
It received 1 comments.

PULL REQUESTS

This week, no pull requests has been proposed by the users.

CONTRIBUTORS

This week, 3 users have contributed to this repository.
They are atmadeep, lgh5054, and weiyaoxing.

STARGAZERS

This week, no user has starred this repository.

COMMITS

This week, there have been 2 commits in the repository.
These are:
🛠️ Update hardware_tut2.md by ninawrong
🛠️ Update hardware_tut2.md by ninawrong

RELEASES

This week, no releases were published.

That's all for this week, please watch 👀 and star ⭐ generalized-intelligence/GAAS to receive next weekly updates. 😃

Didn't find any ros topic about camera data

In your tutorial, after running rostopic list, there are 2 topics called /gi/simulation/XX/image_raw.
But, I follow your tutorial on gitbook and build from source, when I get into the part2, I can't find anything about the camera and I don't know how to use the slam and SfM simulation.
Then I use the docker way for making sure that I didn't miss any tiny. But, still, when I tap in 'rostopic list', /gi doesn't show up.

Did I forget building the "gi package" or something related?

PS: when the next video will be released? XD

THX!

跟着gitbook的教程走,part1 还好说,part2的时候卡住了,毫无头绪,斗胆来issue提问下。找不到相机数据那个topic,是不是得自己设置相机。还有如何安装,调用slam模块?

ResourceNotFoundError: gazebo_ros. Cannot run the first tutorial

  • Tutorial No.: 1
  • ROS: Kinetic
  • Gazebo: 7
  • Ubuntu: 16.04
  • System Platform: X64

Expected Behavior

Gazebo simulation window should pop up with the drone centered in middle.

Current Behavior

Error on terminal :
ResourceNotFound: gazebo_ros

Failure Logs

roslaunch px4 mavros_posix_sitl.launch
... logging to /home/atmadeep/.ros/log/ff7c2de2-ac81-11e9-915b-3497f6e05201/roslaunch-osiris-21857.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

Traceback (most recent call last):
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/init.py", line 306, in main
p.start()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/parent.py", line 268, in start
self._start_infrastructure()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/parent.py", line 217, in _start_infrastructure
self._load_config()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/parent.py", line 132, in _load_config
roslaunch_strs=self.roslaunch_strs, verbose=self.verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/config.py", line 451, in load_config_default
loader.load(f, config, verbose=verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 749, in load
self._load_launch(launch, ros_config, is_core=core, filename=filename, argv=argv, verbose=verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 721, in _load_launch
self._recurse_load(ros_config, launch.childNodes, self.root_context, None, is_core, verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 685, in _recurse_load
val = self._include_tag(tag, context, ros_config, default_machine, is_core, verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 95, in call
return f(*args, **kwds)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 627, in _include_tag
default_machine, is_core, verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 685, in _recurse_load
val = self._include_tag(tag, context, ros_config, default_machine, is_core, verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 95, in call
return f(*args, **kwds)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 589, in _include_tag
inc_filename = self.resolve_args(tag.attributes['file'].value, context)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 183, in resolve_args
return substitution_args.resolve_args(args, context=context.resolve_dict, resolve_anon=self.resolve_anon)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 370, in resolve_args
resolved = _resolve_args(resolved, context, resolve_anon, commands)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 383, in _resolve_args
resolved = commands[command](resolved, a, args, context)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 151, in _find
source_path_to_packages=source_path_to_packages)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 197, in _find_executable
full_path = _get_executable_path(rp.get_path(args[0]), path)
File "/usr/lib/python2.7/dist-packages/rospkg/rospack.py", line 203, in get_path
raise ResourceNotFound(name, ros_paths=self._ros_paths)
ResourceNotFound: gazebo_ros
ROS path [0]=/opt/ros/kinetic/share/ros
ROS path [1]=/opt/ros/kinetic/share
ROS path [2]=/home/atmadeep/catkin_ws/src/Firmware
ROS path [3]=/home/atmadeep/catkin_ws/src/Firmware/Tools/sitl_gazebo

make posix_sitl_default gazebo-ERROR:recipe for target 'gazebo' failed

Perform the following two steps,and report errors
cd Firmware
make posix_sitl_default gazebo

specific output:
root@zdd-P45VJ:/home/zdd/GAAS/catkin_ws/src/Firmware#` make posix_sitl_default gazebo -j1
[ 0%] Built target git_gazebo
[ 2%] Built target df_driver_framework
[ 3%] Built target mixer_gen
[ 3%] Built target uorb_headers
[ 4%] Built target git_driverframework
[ 4%] Built target mixer_gen_6dof
[ 4%] Built target git_ecl
[ 4%] Built target git_gps_devices
[ 4%] Built target git_mavlink_v2
[ 5%] Generating ../../logs
[ 8%] Built target work_queue
[ 8%] No forceconfigure step for 'sitl_gazebo'
[ 8%] Built target logs_symlink
[ 8%] Performing configure step for 'sitl_gazebo'
[ 8%] Built target tinybson
-- install-prefix: /usr/local
[ 24%] Built target uorb_msgs
[ 25%] Built target ecl_airdata
[ 25%] Built target perf
[ 25%] Built target ecl_attitude_fw
[ 26%] Built target ecl_geo
-- Boost version: 1.58.0
-- Found the following Boost libraries:
-- system
-- thread
-- timer
-- chrono
-- date_time
-- atomic
[ 26%] Built target ecl_geo_lookup
[ 27%] Built target mixer
[ 28%] Built target ecl_tecs
[ 28%] Built target ecl_validation
-- Boost version: 1.58.0
[ 29%] Built target rc
[ 29%] Built target generate_topic_listener
[ 30%] Built target px4_layer
[ 31%] Built target parameters
[ 31%] Built target ecl_l1
[ 32%] Built target battery
-- Building klt_feature_tracker without catkin
[ 32%] Built target airspeed
-- Building OpticalFlow with OpenCV
[ 32%] Built target circuit_breaker
[ 34%] Built target controllib
[ 34%] Built target conversion
[ 35%] Built target drivers__device
[ 35%] Built target mathlib
[ 36%] Built target pid
[ 36%] Built target pwm_limit
[ 38%] Built target flight_tasks
[ 39%] Built target terrain_estimation
[ 40%] Built target tunes
[ 40%] Built target version
[ 40%] Built target platforms__common
[ 40%] Built target drivers_board
[ 41%] Built target systemlib
[ 41%] Built target launchdetection
[ 42%] Built target drivers__airspeed
[ 42%] Built target runway_takeoff
-- catkin DISABLED
Gazebo version: 7.0
-- Using C++17 compiler
[ 42%] Built target drivers__led
[ 44%] Built target ecl_EKF
[ 45%] Built target modules__uORB
[ 45%] Built target drivers__ets_airspeed
[ 45%] Built target drivers__ms4525_airspeed
-- Configuring done
[ 45%] Built target drivers__sdp3x_airspeed
[ 46%] Built target drivers__ll40ls
[ 47%] Built target drivers__ms5525_airspeed
[ 47%] Built target drivers__mb12xx
[ 48%] Built target drivers__sf0x
[ 50%] Built target drivers__sf1xx
[ 51%] Built target drivers__tfmini
[ 51%] Built target drivers__teraranger
[ 51%] Built target drivers__srf02
[ 51%] Built target drivers__leddar_one
[ 51%] Built target drivers__ulanding
Scanning dependencies of target drivers__batt_smbus
[ 51%] Built target drivers__vl53lxx
Scanning dependencies of target drivers__camera_trigger
Scanning dependencies of target drivers__gps
[ 51%] Building CXX object src/drivers/batt_smbus/CMakeFiles/drivers__batt_smbus.dir/batt_smbus.cpp.o
[ 51%] Building CXX object src/drivers/camera_trigger/CMakeFiles/drivers__camera_trigger.dir/camera_trigger.cpp.o
[ 51%] Building CXX object src/drivers/gps/CMakeFiles/drivers__gps.dir/gps.cpp.o
[ 51%] Linking CXX static library libdrivers__batt_smbus.a
[ 51%] Building CXX object src/drivers/camera_trigger/CMakeFiles/drivers__camera_trigger.dir/interfaces/src/camera_interface.cpp.o
[ 51%] Built target drivers__batt_smbus
Scanning dependencies of target drivers__pwm_out_sim
[ 51%] Building CXX object src/drivers/gps/CMakeFiles/drivers__gps.dir/devices/src/gps_helper.cpp.o
[ 51%] Building CXX object src/drivers/camera_trigger/CMakeFiles/drivers__camera_trigger.dir/interfaces/src/pwm.cpp.o
[ 51%] Building CXX object src/drivers/pwm_out_sim/CMakeFiles/drivers__pwm_out_sim.dir/PWMSim.cpp.o
[ 51%] Building CXX object src/drivers/camera_trigger/CMakeFiles/drivers__camera_trigger.dir/interfaces/src/seagull_map2.cpp.o
[ 52%] Building CXX object src/drivers/camera_trigger/CMakeFiles/drivers__camera_trigger.dir/interfaces/src/gpio.cpp.o
[ 52%] Linking CXX static library libdrivers__camera_trigger.a
[ 53%] Building CXX object src/drivers/gps/CMakeFiles/drivers__gps.dir/devices/src/mtk.cpp.o
[ 53%] Built target drivers__camera_trigger
[ 53%] Building CXX object src/drivers/gps/CMakeFiles/drivers__gps.dir/devices/src/ashtech.cpp.o
-- Generating done
-- Build files have been written to: /home/zdd/GAAS/catkin_ws/src/Firmware/build/posix_sitl_default/build_gazebo
[ 53%] Performing build step for 'sitl_gazebo'
[ 53%] Building CXX object src/drivers/gps/CMakeFiles/drivers__gps.dir/devices/src/ubx.cpp.o
[ 53%] Linking CXX static library libdrivers__pwm_out_sim.a
make[7]: *** No rule to make target '/home/zdd/GAAS/catkin_ws/src/Firmware/Tools/sitl_gazebo/PROTOBUF_PROTOC_EXECUTABLE-NOTFOUND', needed by 'OpticalFlow.pb.cc'。 停止。
CMakeFiles/Makefile2:67: recipe for target 'CMakeFiles/sensor_msgs.dir/all' failed
make[6]: *** [CMakeFiles/sensor_msgs.dir/all] Error 2
Makefile:149: recipe for target 'all' failed
make[5]: *** [all] Error 2
platforms/posix/CMakeFiles/sitl_gazebo.dir/build.make:112: recipe for target 'external/Stamp/sitl_gazebo/sitl_gazebo-build' failed
make[4]: *** [external/Stamp/sitl_gazebo/sitl_gazebo-build] Error 2
CMakeFiles/Makefile2:15276: recipe for target 'platforms/posix/CMakeFiles/sitl_gazebo.dir/all' failed
make[3]: *** [platforms/posix/CMakeFiles/sitl_gazebo.dir/all] Error 2
make[3]: *** 正在等待未完成的任务....
[ 53%] Built target drivers__pwm_out_sim
[ 53%] Linking CXX static library libdrivers__gps.a
[ 53%] Built target drivers__gps
CMakeFiles/Makefile2:17990: recipe for target 'platforms/posix/CMakeFiles/gazebo.dir/rule' failed
make[2]: *** [platforms/posix/CMakeFiles/gazebo.dir/rule] Error 2
Makefile:5681: recipe for target 'gazebo' failed
make[1]: *** [gazebo] Error 2
Makefile:148: recipe for target 'posix_sitl_default' failed
make: *** [posix_sitl_default] Error 2

Weekly Digest (26 May, 2019 - 2 June, 2019)

Here's the Weekly Digest for generalized-intelligence/GAAS:


ISSUES

Last week 2 issues were created.
Of these, 0 issues have been closed and 2 issues are still open.

OPEN ISSUES

💚 #36 website redesigning , by rishav30sh
💚 #35 SITL simulation of combination of gps and slam navigation, by guoxianzhen

LIKED ISSUE

👍 #36 website redesigning , by rishav30sh
It received 👍 x1, 😄 x0, 🎉 x0 and ❤️ x0.

NOISY ISSUE

🔈 #36 website redesigning , by rishav30sh
It received 1 comments.


PULL REQUESTS

Last week, no pull requests were created, updated or merged.


COMMITS

Last week there were 16 commits.
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong
🛠️ Create readme.md by ninawrong
🛠️ Add tracking demo gif by hddgi
🛠️ Update Object-Tracking link by hddgi
🛠️ fixed memory error(in edgeprv's vertice size);TODO:fix Jacobians in edge prv and remove dependency of GPS msg. by cyanine-gi
🛠️ Merge branch 'master' of https://github.com/generalized-intelligence/GAAS by cyanine-gi
🛠️ added edgeprv;still fixing memory error in g2o. by cyanine-gi
🛠️ add PCL filters to generated filter for better result by Doodle1106
🛠️ fix scale error by Doodle1106
🛠️ add image for qrcode model by Doodle1106
🛠️ fix solution selection by Doodle1106
🛠️ Update README.md by ninawrong
🛠️ Update README.md by ninawrong


CONTRIBUTORS

Last week there were 4 contributors.
👤 ninawrong
👤 hddgi
👤 cyanine-gi
👤 Doodle1106


STARGAZERS

Last week there were 18 stagazers.
georgeweifly
Kerorohu
luofeixiang
sdjkxhb2016
jingqiuav
mexbo
skx1995
pp-user
XiaoJake
TobiMiller
robin-shaun
inkasaras
arpad-gabor
linhartr22
goldenite
TangHsiangYu
why-freedom
Toothsmile
You all are the stars! 🌟


RELEASES

Last week there were no releases.


That's all for last week, please 👀 Watch and Star the repository generalized-intelligence/GAAS to receive next weekly updates. 😃

You can also view all Weekly Digests by clicking here.

Your Weekly Digest bot. 📆

SITL simulation of combination of gps and slam navigation

Please provide any relevant information about your setup.

  • Tutorial No.:[Tutorial 3]
  • Mavros: [0.18.4]
  • ROS: [Kinetic]
  • Gazebo: [7]
  • Ubuntu: [16.04]
  • System Platform: [X86]
    I have implemented the tutorial 3 for SLAM navigation. However, my final year projection is about combination of slam and gps navigation. I am wondering if i can use GAAS for my fyp.
    I replace the modeled iris copter used in tutorial 3 with iris_stereo_gray_gps. Then SLAM is launched and EKF2_AID_MASK is configured to 9 which allows for gps and vision pose fusion.
    Then, the copter takes off under gps and slam navigation. I close GPS with command "gpssim stop" when the copter is hovering after taking off. The copter keep hovering without GPS and it can implement simple mission like fly 6 meter to the right then land under SLAM navigation. So I think these steps may work.
    But I have not tried any complicate simulation like closing GPS while copter is moving. I am not sure if the previous steps are right. Do I need to do any configuration after closing GPS?

Screenshots

image
Here is the position information of my simulation. The dashed lines represent vision pose, The thin lines are local positions from estimator and the thick lines are local positions from GPS.

How to use mavros Publish a XYZ data to put the aircraft in 3DFIX without GPS?

geometry_msgs::PoseStamped vision;
int main(int argc, char **argv)
{
ros::init(argc, argv, "uwb");
ros::NodeHandle nh("~");
ros::Publisher vision_pub = nh.advertise<geometry_msgs::PoseStamped>("/mavros/vision_pose/pose", 100);

// 频率
ros::Rate rate(20.0);
while (ros::ok())
{
	//回调一次 更新传感器状态
	ros::spinOnce();
	vision.pose.position.x = 116.3;
	vision.pose.position.y = 39.9;
	vision.pose.position.z = 3;

	vision.pose.orientation.x = 0.707107;
	vision.pose.orientation.y = 0;
	vision.pose.orientation.z = 0;
	vision.pose.orientation.w = 0.707107;

	vision.header.stamp = ros::Time::now();
	vision_pub.publish(vision);

	rate.sleep();
}
return 0;

}
I want to use this demo, put the aircraft in 3DFIX without GPS,but it not work。

When starting launch files via roslaunch "roslaunch px4 sfm.launch"- ERROR [px4] Error opening startup file, does not exist: etc/init.d/rcS

Followiing is the log:

lulu@lulu-Vostro-3668:~$ roslaunch px4 sfm.launch
... logging to /home/lulu/.ros/log/3014fc68-5133-11e9-b6c3-3cf862c629e7/roslaunch-lulu-Vostro-3668-22089.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://lulu-Vostro-3668:45265/

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/cmd/use_comp_id_system_control: False
 * /mavros/conn/heartbeat_rate: 1.0
 * /mavros/conn/system_time_rate: 1.0
 * /mavros/conn/timeout: 10.0
 * /mavros/conn/timesync_rate: 10.0
 * /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
 * /mavros/distance_sensor/hrlv_ez4_pub/id: 0
 * /mavros/distance_sensor/hrlv_ez4_pub/orientation: PITCH_270
 * /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/laser_1_sub/id: 3
 * /mavros/distance_sensor/laser_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/laser_1_sub/subscriber: True
 * /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
 * /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
 * /mavros/distance_sensor/lidarlite_pub/id: 1
 * /mavros/distance_sensor/lidarlite_pub/orientation: PITCH_270
 * /mavros/distance_sensor/lidarlite_pub/send_tf: True
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/sonar_1_sub/id: 2
 * /mavros/distance_sensor/sonar_1_sub/orientation: PITCH_270
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/fake_gps/eph: 2.0
 * /mavros/fake_gps/epv: 2.0
 * /mavros/fake_gps/fix_type: 3
 * /mavros/fake_gps/geo_origin/alt: 408.0
 * /mavros/fake_gps/geo_origin/lat: 47.3667
 * /mavros/fake_gps/geo_origin/lon: 8.55
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/mocap_transform: True
 * /mavros/fake_gps/satellites_visible: 5
 * /mavros/fake_gps/tf/child_frame_id: fix
 * /mavros/fake_gps/tf/frame_id: map
 * /mavros/fake_gps/tf/listen: False
 * /mavros/fake_gps/tf/rate_limit: 10.0
 * /mavros/fake_gps/tf/send: False
 * /mavros/fake_gps/use_mocap: True
 * /mavros/fake_gps/use_vision: False
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: udp://:14540@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.000349065850399
 * /mavros/imu/frame_id: base_link
 * /mavros/imu/linear_acceleration_stdev: 0.0003
 * /mavros/imu/magnetic_stdev: 0.0
 * /mavros/imu/orientation_stdev: 1.0
 * /mavros/local_position/frame_id: map
 * /mavros/local_position/tf/child_frame_id: base_link
 * /mavros/local_position/tf/frame_id: map
 * /mavros/local_position/tf/send: False
 * /mavros/local_position/tf/send_fcu: False
 * /mavros/mission/pull_after_gcs: True
 * /mavros/mocap/use_pose: True
 * /mavros/mocap/use_tf: False
 * /mavros/odometry/in/child_frame_id: base_link
 * /mavros/odometry/in/frame_id: odom
 * /mavros/odometry/in/frame_tf/body_frame_orientation: flu
 * /mavros/odometry/in/frame_tf/local_frame: local_origin_ned
 * /mavros/odometry/out/frame_tf/body_frame_orientation: frd
 * /mavros/odometry/out/frame_tf/local_frame: vision_ned
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682389136
 * /mavros/px4flow/ranger_max_range: 5.0
 * /mavros/px4flow/ranger_min_range: 0.3
 * /mavros/safety_area/p1/x: 1.0
 * /mavros/safety_area/p1/y: 1.0
 * /mavros/safety_area/p1/z: 1.0
 * /mavros/safety_area/p2/x: -1.0
 * /mavros/safety_area/p2/y: -1.0
 * /mavros/safety_area/p2/z: -1.0
 * /mavros/setpoint_accel/send_force: False
 * /mavros/setpoint_attitude/reverse_thrust: False
 * /mavros/setpoint_attitude/tf/child_frame_id: target_attitude
 * /mavros/setpoint_attitude/tf/frame_id: map
 * /mavros/setpoint_attitude/tf/listen: False
 * /mavros/setpoint_attitude/tf/rate_limit: 50.0
 * /mavros/setpoint_attitude/use_quaternion: False
 * /mavros/setpoint_position/mav_frame: LOCAL_NED
 * /mavros/setpoint_position/tf/child_frame_id: target_position
 * /mavros/setpoint_position/tf/frame_id: map
 * /mavros/setpoint_position/tf/listen: False
 * /mavros/setpoint_position/tf/rate_limit: 50.0
 * /mavros/setpoint_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: map
 * /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: map
 * /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: map
 * /mavros/wheel_odometry/tf/send: True
 * /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: kinetic
 * /rosversion: 1.12.14
 * /use_sim_time: True

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

ROS_MASTER_URI=http://localhost:11311

process[sitl-1]: started with pid [22111]
INFO  [px4] Creating symlink /home/lulu/src/Firmware -> /home/lulu/.ros/etc
ERROR [px4] Error opening startup file, does not exist: etc/init.d/rcS
process[gazebo-2]: started with pid [22112]
process[gazebo_gui-3]: started with pid [22117]
process[vehicle_spawn_lulu_Vostro_3668_22089_7992864178812158555-4]: started with pid [22122]
================================================================================REQUIRED process [sitl-1] has died!
process has died [pid 22111, exit code 255, cmd /home/lulu/src/Firmware/build/px4_sitl_default/bin/px4 /home/lulu/src/Firmware /home/lulu/src/Firmware/posix-configs/SITL/init/ekf2/iris_stereo_rgb_gps __name:=sitl __log:=/home/lulu/.ros/log/3014fc68-5133-11e9-b6c3-3cf862c629e7/sitl-1.log].
log file: /home/lulu/.ros/log/3014fc68-5133-11e9-b6c3-3cf862c629e7/sitl-1*.log
Initiating shutdown!
================================================================================
process[mavros-5]: started with pid [22123]
[ INFO] [1553823913.485295611]: FCU URL: udp://:14540@localhost:14557
[ INFO] [1553823913.486700214]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1553823913.486768007]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1553823913.486852512]: GCS bridge disabled
[ INFO] [1553823913.497186098]: Plugin 3dr_radio loaded
[ INFO] [1553823913.499117810]: Plugin 3dr_radio initialized
[ INFO] [1553823913.499216267]: Plugin actuator_control loaded
[ INFO] [1553823913.503447224]: Plugin actuator_control initialized
[ INFO] [1553823913.503537213]: Plugin altitude loaded
[ INFO] [1553823913.504373639]: Plugin altitude initialized
[ INFO] [1553823913.504442511]: Plugin command loaded
[ INFO] [1553823913.508733130]: Plugin command initialized
[ INFO] [1553823913.508822193]: Plugin ftp loaded
[mavros-5] killing on exit
[ERROR] [1553823913.512777707]: [registerService] Failed to contact master at [localhost:11311].  Retrying...
[vehicle_spawn_lulu_Vostro_3668_22089_7992864178812158555-4] killing on exit
[gazebo_gui-3] killing on exit
[sitl-1] killing on exit
Traceback (most recent call last):
  File "/opt/ros/kinetic/lib/gazebo_ros/spawn_model", line 21, in <module>
    import rospy, sys, os, time
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/__init__.py", line 49, in <module>
    from .client import spin, myargv, init_node, \
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/client.py", line 54, in <module>
[gazebo-2] killing on exit
    import rospy.core
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/core.py", line 66, in <module>
    import rosgraph.roslogging
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosgraph/roslogging.py", line 41, in <module>
    import logging.config
  File "/usr/lib/python2.7/logging/config.py", line 489, in <module>
    class DictConfigurator(BaseConfigurator):
KeyboardInterrupt
shutting down processing monitor...
... shutting down processing monitor complete
done

"roslaunch px4 sfm.launch" cannot connect mavros

when the command roslaunch px4 sfm.launch was finished ,I inputed rostopic echo /mavros/state

lulu@lulu-Vostro-3668:~$ rostopic echo /mavros/state
header: 
  seq: 0
  stamp: 
    secs: 0
    nsecs:         0
  frame_id: ''
connected: False
armed: False
guided: False
mode: ''
system_status: 0
---

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.