Show EOL distros:
Package Summary
This package is used to communicate between drone and PC/Laptop through ROS. Drone will send the accelerometer,gyroscope, magnetometer and altitude data. You can subscribe to the roll, pitch, yaw and battery level
- Maintainer status: developed
- Maintainer: Simranjeet Singh <simranjeet AT cse.iitb.ac.in DOT com>
- Author: Simranjeet Singh <simranjeet AT cse.iitb.ac DOT in>
- License: BSD
- Source: git https://github.com/simmubhangu/eyantra_drone.git (branch: master)
Package Summary
This package is used to communicate between drone and PC/Laptop through ROS. Drone will send the accelerometer,gyroscope, magnetometer and altitude data. You can subscribe to the roll, pitch, yaw and battery level
- Maintainer status: developed
- Maintainer: Simranjeet Singh <simranjeet AT cse.iitb.ac.in DOT com>
- Author: Simranjeet Singh <simranjeet AT cse.iitb.ac DOT in>
- License: BSD
- Source: git https://github.com/simmubhangu/eyantra_drone.git (branch: master)
Contents
Note: Current package is for Pluto drone by DronaAviation. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Tutorial Level: BEGINNER
Next Tutorial: Multi_drone(Swarm)
Prerequisites
# libavcodec and libsdl2-dev for camera sudo apt install libavcodec-dev libsdl2-dev
Installation
# Navigate to your catkin workspace cd <WORKSPACE_NAME>/src # clone repository git clone https://github.com/simmubhangu/eyantra_drone.git # Build the Package catkin_make
Run Package
First connect to the drones wifi. Run roscore command and follow the step:
rosrun edrone_server data_via_rosservice.py
roslaunch edrone_server drone_comb.launch
Services
/droneservice(edrone_services): Drone gives data on this service after request. This service gives the data like accelerometer, gyro, Magneto and altitude.
Topic
/drone_command(edrone_msgs): This topic used to give the motion command to drone
/drone_cam(sensor_msgs): This topic can be used to get the camera feed. This is only for the on-board camera drone variation.
Keyboard keys to control the Drone
- Contolling Drone
You can control your drone after launching the drone_comb.launch. Type the following sequence to control the drone in particular coordinates.
NOTE: The key pressed will not be visible in the terminal.
Control Your eDrone! --------------------------- Moving around: u i o j k l m a : Arm drone d : Dis-arm drone w : Increase Altitude s : Increase Altitude u,o: Change Yaw CTRL-C to quit
Control Commands (varies from 1000 to 2000: Default- 1500)
- Arm
rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1500, rcYaw: 1500, rcThrottle: 1000, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}"
- Disarm
rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1500, rcYaw: 1500, rcThrottle: 1000, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1000}"
- Motion Command: You can set the rcRoll, rcPitch , rcYaw and rcThrottle to control the direction of drone.
# Increase Roll value to move forward with respect to x-axis rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1600, rcPitch: 1500, rcYaw: 1500, rcThrottle: 1500, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}" # Decrease Roll value to move backward with respect to x-axis rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1400, rcPitch: 1500, rcYaw: 1500, rcThrottle: 1500, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}" # Increase Pitch value to move forward/left with respect to y-axis rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1600, rcYaw: 1500, rcThrottle: 1500, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}" # Decrease Pitch value to move backward/right with respect to y-axis rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1400, rcYaw: 1500, rcThrottle: 1500, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}" # Increase Throttle value to move up with respect to z-axis rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1500, rcYaw: 1500, rcThrottle: 1600, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}" # Decrease Throttle value to move down with respect to z-axis rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1500, rcYaw: 1500, rcThrottle: 1400, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}" # Increase Yaw value to rotate in clockwise direction rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1500, rcYaw: 1600, rcThrottle: 1500, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}" # decrease Yaw value to rotate in anti-clockwise direction rostopic pub /drone_command edrone_client/edrone_msgs "{rcRoll: 1500, rcPitch: 1500, rcYaw: 1400, rcThrottle: 1500, rcAUX1: 0, rcAUX2: 0, rcAUX3: 0, rcAUX4: 1500}"
Contact
Developed by e-Yantra at IIT bombay