-
Notifications
You must be signed in to change notification settings - Fork 5
Using MAVROS
This page provides some general information about the use of MAVROS for LoCO. It's not specific to any part of the assembly and is thus not linked in any of the main pages.
QGroundControl allows a user to see actual values the PixHawk is receiving and sending rather than ROS reported values. To access this functionality, connect to the PixHawk with the micro USB cable (make sure you know how to do this properly!) and open up QGroundControl. In the very top left corner, click on the Widgets menu, then MAVLink Inspector. Double click on Vehicle 1, then you should see all the real time values associated with the robot.
To read MAVROS topics from the Raspberry Pi, run the command rosservice call /mavros/set_stream_rate 0 10 1
to set the data stream rate. Then call rostopic list
to view available topics. Finally, rostopic echo [topic]
to view the data.
The PixHawk has a few safeties, mainly the disarmed/armed modes. When disarmed, the PixHawk will not send output to motors and other devices, even if there is joystick input. When armed, the PixHawk will send output. If the PixHawk loses connection to the master ROS node, it will automatically disarm.
When armed, the PixHawk's large LED will be solid blue. When disarmed, the LED will be blinking blue.
You can see the armed/disarmed status and flight mode in QGroundControl when you're connected to the PixHawk via a micro USB cable. It's on the top ribbon of the flight screen. To manually arm the PixHawk, double click "Disarmed", then a slider should appear at the bottom of the screen. Slide to arm. To disarm, click "Armed" and follow the same procedure.
We can arm the PixHawk from the Raspberry Pi as well. Use the command rosservice call /mavros/cmd/arming "value: true"
. To disarm, replace "value: true"
with "value: false"
.
The PixHawk also has multiple flight modes. The one we're interested is Manual Flight Mode.
To enter manual flight mode, click the flight mode to the left of the armed/disarmed status. Then select "Manual".
From the Raspberry Pi, use the command rosservice call /mavros/set_mode 0 'MANUAL'
Ensure the PixHawk is in Manual flight mode. Arm the PixHawk with the command Use this command to manually set the RC values going to the PixHawk:
rostopic pub -r 10 /mavros/rc/override mavros_msgs/OverrideRCIn "channels: [1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500]"
Each channel has a minimum value of 1100 (full reverse), a max of 1900 (full forward), and neutral at 1500.
The channels in the array are
[0]: Not used, always send 1500
[1]: Not used, always send 1500
[2]: Pitch
[3]: Yaw (Inverted)
[4]: Throttle
[5]: Not used, always send 1500
[6]: Not used, always send 1500
[7]: Not used, always send 1500
Everything discussed up to this point can be implemented in Python. We'll look through our teleop code for the specific functionality we discussed above. There is also the MAVROS wiki that has MAVROS specifications, and the PX4 documentation that has some example pieces of code including Gazebo simulation.
This hasn't been implemented in the teleop code.
from mavros_msgs.srv import StreamRate
import rospy
def set_stream_rate():
stream_rate = rospy.ServiceProxy('mavros/set_stream_rate', StreamRate)
stream_rate(0, 10, 1)
Sets the data stream rate (stream_rate(0, 10, 1)
) to 10 Hz.
import mavros
import mavros.command
def arm():
mavros.set_namespace()
mavros.command.arming(True)
Set the mavros namespace, then arm the robot. Replace True
with False
to disarm.
import rospy
from mavros_msgs.srv import SetMode
def set_manual_mode():
set_mode = rospy.ServiceProxy('mavros/set_mode', SetMode)
rospy.wait_for_service('mavros/set_mode')
set_mode(0, 'MANUAL')
Waits for the master node to boot up, then sets the flight mode to MANUAL
.
import rospy
from sensor_msgs.msg import Joy
from mavros_msgs.msg import OverrideRCIn as rc
pubRC = None
msg = None
neutral_speed = 1500
Importing everything, instantiating global variables, and declaring the value for neutral_speed.
def convert_joy_units(data):
#This takes the float value from -1.0 to 1.0 and converts it to a value between 1100 and 1900
return int((data * 400) + neutral_speed)
def joy_callback(data):
global pubRC, msg
(yaw, pitch, _, throttle, _, _) = data.axes
msg = rc()
msg.channels[0] = neutral_speed
msg.channels[1] = neutral_speed
msg.channels[2] = convert_joy_units(pitch)
msg.channels[3] = convert_joy_units(yaw*-1)
msg.channels[4] = convert_joy_units(throttle)
def init_joy_control():
global pubRC
pubRC = rospy.Publisher('mavros/rc/override', rc, queue_size=10)
rospy.Subscriber("/joy", Joy, joy_callback)
We have a function that converts our joystick input to an rc friendly output. We define a function that grabs the joystick data, pushes it through the converter function, then assigns the output to the specific rc channels. Finally, we create a publisher to the rc topic, and a subscriber to the joy node topic and assign the callback function.
This wiki is a living document and may be updated as new information becomes available.
If you find an error in the documentation or something insufficiently explained, submit an issue on this repository.
- Design Improvements
- Parts List
- Fabricating Mounting Structures (General Instructions)
- Power System Assembly
- Thruster System Assembly
- Computing System Assembly
- Networking Assembly and Tether
- Sensor Assembly
- OLED Assembly
- Enclosure Assembly (Left)
- Enclosure Assembly (Right)
- Final Assembly