Package Summary
The heifu metapackage that installs all heifu related packages.
- Maintainer status: maintained
- Maintainer: André Ferreira <andre.ferreira AT beyond-vision DOT pt>, Fábio Azevedo <fabio.azevedo AT beyond-vision DOT pt>
- Author: André Ferreira <andre.ferreira AT beyond-vision DOT pt>
- License: BSD
- Source: git https://gitlab.pdmfc.com/drones/ros1/heifu.git (branch: releasePackage)
Documentation
Installation
ROS packages dependences:
GeographicLib dependeces:
sudo apt-get install libgeographic-dev sudo apt-get install geographiclib-tools
Run the script in: install_geographiclib_datasets.sh
Compile this directory in your ROS workspace.
Then copy the already configured files to the *mavros* directory:
cd ${YOUR_ROS_WORKSPACE}/src/heifu/heifu_scripts_firmware
cp apm_config.yaml $(rospack find mavros)/launch/
cp apm.launch $(rospack find mavros)/launch/
cp node.launch $(rospack find mavros)/launch/NOTE: Adjust the yaml loader script to deal with the argument substitution in the roslaunch of yaml files:
cd ${YOUR_ROS_WORKSPACE}/src/heifu/heifu_scripts_firmware
cp loader.py /opt/ros/melodic/lib/python2.7/dist-packages/roslaunch/Dont forget to add gimbal and mavros to the source folder and run catkin build
To run the nodes with a real drone:
Just launch - Heifu_bringup
roslaunch heifu_bringup heifu_bringup.launch
Launch Input arguments:
    argSafety - Activates the safety zone mode and run the node heifu_safety.
    argTakeOffAltitude - Defines the Takeoff altitude.
    argSim - Activates the simulation mode. Loads Gazebo and a pre-configured world with the drone HEIFU.
    argSecredas - Activates the Secredas Usecases. (Needs extra packages secredas).
    argUseCase - Defines witch usecase of Secredas will be loaded.
    argPlanners - Loads the Planners nodes with static colision avoidance (Needs extra packages Planners).
Heifu Simulation:
First make sure that the ArduPilot firmware is correctly installed, by following the steps described https://gitlab.pdmfc.com/drones/heifu/wikis/Install-and-Configure-ArduPilot-Firmware.
To open the simulation:
1st terminal - Launch Heifu_bringup
roslaunch heifu_bringup heifu_bringup.launch argSim:=true
2nd terminal - Launch ArduPilot firmware
cd ~/ardupilot/ArduCopter/ sim_vehicle.py -v ArduCopter -f gazebo-heifu -I1
Packages
Heifu Bringup
Responsible for load all packages.
Heifu Description
This package contains the drone robot HEIFU and the worlds for the simulation.
Heifu Diagnostic
Responsible for verify the GPS fix state of the drone and send the information to the application.
Subscribers:
- /diagnostics diagnostic_msgs/DiagnosticArray 
Publishers:
- /heifu/g/f/m std_msgs/Int8 
Heifu Interface
This package is the bridge between the ROS and the application.
Subscribers:
- /heifu/disarm std_msgs/Empty 
- /heifu/takeoff std_msgs/Empty 
- /heifu/land std_msgs/Empty 
- /heifu/mavros/local_position/pose geometry_msgs/PoseStamped 
- /heifu/mavros/local_position/velocity_local geometry_msgs/TwistStamped 
- /heifu/mavros/global_position/global sensor_msgs/NavSatFix 
- /heifu/mavros/state mavros_msgs/State 
- /heifu/c/s std_msgs/String 
- /heifu/mavros/battery sensor_msgs/BatteryState 
- /heifu/mavros/global_position/raw/satellites std_msgs/UInt32 
- /heifu/g/f/m std_msgs/String 
Publishers:
- /warning std_msgs/String 
- /heifu/frontend/cmd geometry_msgs/Twist 
- /heifu/land std_msgs/Empty 
- /heifu/takeoff std_msgs/Empty 
- /heifu/mode_auto std_msgs/Empty 
- /heifu/rtl std_msgs/Empty 
- /heifu/global_setpoint_converter geographic_msgs/GeoPose 
Services:
- /heifu/mavros/mission/clear mavros_msgs/WaypointPush 
- /heifu/mavros/set_mode mavros_msgs/SetMode 
- /heifu/mavros/cmd/arming mavros_msgs/CommandBool 
Heifu Mavros
This is the main package to control the drone. Responsible for message conversions and commands between the packages and the mavros node.
Subscribers:
- /heifu/takeoff std_msgs/Empty 
- /heifu/land std_msgs/Empty 
- /heifu/disarm std_msgs/Empty 
- /heifu/cmd_vel geometry_msgs/Twist 
- /heifu/xbox_vel_raw geometry_msgs/Twist 
- /heifu/mavros/local_position/pose geometry_msgs/PoseStamped 
- /heifu/rtl std_msgs/Empty 
- /heifu/land_vel_raw geometry_msgs/Twist 
- /heifu/simulation_raw geometry_msgs/Twist 
- /heifu/frontend/cmd geometry_msgs/Twist 
- /heifu/mode_auto std_msgs/Empty 
- /heifu/global_setpoint_converter geographic_msgs/GeoPose 
- /heifu/mission/start std_msgs/Empty 
- /heifu/mission/stop std_msgs/Empty 
Publishers:
- /heifu/mavros/setpoint_velocity/cmd_vel geometry_msgs/TwistStamped 
- /heifu/xbox_vel geometry_msgs/Twist 
- /heifu/land_vel geometry_msgs/Twist 
- /heifu/simulation geometry_msgs/Twist 
- /heifu//g/f/m std_msgs/Int8 
- /heifu/mavros/setpoint_position/local geometry_msgs/PoseStamped 
Services:
- /heifu/mavros/cmd/arming mavros_msgs/CommandBool 
- /heifu/mavros/set_mode mavros_msgs/SetMode 
- /heifu/mavros/takeoff mavros_msgs/CommandTOL 
Heifu Msgs
This package contain the messages and services necessary to work.
Heifu Safety
If loaded, this package controls the flight area and velocity limit of the drone to a safety real demonstration.
Subscribers:
- /heifu/mavros/local_position/pose geometry_msgs/PoseStamped 
- /heifu/xbox_vel geometry_msgs/Twist 
Publishers:
- /heifu/xbox_vel_safety geometry_msgs/Twist 
Services:
- /heifu/EnableSafetyFence heifu_msgs/EnableSafety 
Heifu Simple Waypoint
This package receive a setpoint and make the drone fly pointed to desired position.
Subscribers:
- /heifu/mission/setpoint geometry_msgs/Pose 
- /heifu/mavros/local_position/pose geometry_msgs/PoseStamped 
Publishers:
- /heifu/mission/start std_msgs/Empty 
- /heifu/mission/stop std_msgs/Empty 
- /heifu/mavros/setpoint_position/local geometry_msgs/PoseStamped 
Heifu Tools
Responsible for convert the velocity command messages.
Subscribers:
- /heifu/joy geometry_msgs/Twist 
Publishers:
- /heifu/dummy_vel geometry_msgs/Twist 
- /heifu/xbox_vel_raw geometry_msgs/Twist 
Report a Bug
Use GitHub to report bugs or submit feature requests. [View active issues]
  
