Slightly off topic but, Patrick, your ROS package has topics like /BlueRov2/servo1/set_pwm and etc. Are these topics used to set the PWM for the thrusters directly? I have tried writing to them but nothing happens so I am just not sure what they are for. Is the a way to PWM the thrusters directly with your package? That is what I am primarily interested in. Thanks for your time.
@brandonk Those topics will only work for outputs that are not configured as motors. There is no way to set pwm to thrusters directly via ROS. You may only set the desired roll/pitch/yaw and forward/up/down.
You can check and see when we will fix this here: https://github.com/bluerobotics/ardusub/issues/166
There is a hack you could do and use the MOTOR_TEST command via mavlink. The command is meant to be used for motor testing, but the logic is almost the same. This will require a pretty high message frequency though, so try higher baudrates.
Hi @brandonk,
Yes, Jacob is correct, the ROS layer only provides access to the mavlink commands, we are always improving ArduSub to allow a more more inputs and controls ![]()
Hi again Patrick!
I want to read the data from the Bar30 pressure sensor with your ROS node.
I can see there are two topics that are being published:
- /mavros/imu/diff_pressure
- /mavros/imu/static_pressure
Does any of this topics publish the bar30 info? Or is it the data from the pixhawk barometer?
Moreover, the name diff_pressure confuses me. Is it a differential value? And in case it is, a difference between what?
Thank you!!! ![]()
Hi,
mavros uses SCALED_PRESSURE (thatâs the internal pixhawk barometer) and not SCALED_PRESSURE2 (that contains bar30 data).
To get the bar30 value, youâll need to create a subscriber to mavlink/from (message type: mavros_msgs/Mavlink) topic, that streams from autopilot the mavlink messages.
We have some pymavlink examples here, you can use it to convert the raw data from the mavros topic to python mavlink structures.
Hello Patrick, thank you for your answer!
I saw that the topic /mavlink/from returns different arrays of values with different IDs. I guess that the IDs in the ROS topics correspond to those of the mavlink messages.
The structure and values of the topic with the SCALED_PRESSURE2 are as follows:
header
seq: 554
stamp
frame_id:
framing_status: 1
magic: 254
len: 14
incompat_flags: 0
compat_flags: 0
seq: 117
sysid: 1
compid: 1
msgid: 137
checksum: 38534
payload64
[0]: 4929168678098075594
[1]: 5078067614371020
signature:
I guess that those two values are the absolute and differential pressure. According to sensor documentation, the bar30 is supposed to provide its readings in mbar; however the values are extremely high! What am I missing?
Thank you again!
Hi,
Sorry for the delay, my virtual machine running ROS was not working properly.
The payload64 list is a bytearray that need to be converted to python structure.
This message has 16 bytes, and the SCALED_PRESSURE2 only uses 14 (uint32_t, float, float, int16_t), so itâs necessary to create a pack/unpack method in python to decode the necessary info:
#!/usr/bin/env python
# ROS module
import rospy
# Mavlink ROS messages
from mavros_msgs.msg import Mavlink
# pack and unpack functions to deal with the bytearray
from struct import pack, unpack
# Topic callback
def callback(data):
# Check if message id is valid (I'm using SCALED_PRESSURE
# and not SCALED_PRESSURE2)
if data.msgid == 29:
rospy.loginfo(rospy.get_caller_id() + " Package: %s", data)
# Transform the payload in a python string
p = pack("QQ", *data.payload64)
# Transform the string in valid values
# https://docs.python.org/2/library/struct.html
time_boot_ms, press_abs, press_diff, temperature = unpack("Iffhxx", p)
def listener():
rospy.init_node('listener', anonymous=True)
rospy.Subscriber("/mavlink/from", Mavlink, callback)
rospy.spin()
if __name__ == '__main__':
listener()
Hi all,
Does anyone have a BlueROV operating successfully on ROS or ROS-2 ?
cheers
Rich
Hi @richard-rickett,
I have done tests a couple of years ago, but you should be fine if you are using mavros and a h264 udp video â ROS video format bridge
Thanks Patrick. This is above my threshold of understanding, Iâm off to find a clever software person to help out ![]()
![]()
Hi, is it possible to connect a BlueRov2 in noetic?
BlueROV2 and ArduSub understand mavlink messages. You can send mavlink messages via mavros. Mavros offers several rostopics and rosservices that you can call to control the vehicle. I managed to get it to run with ROS noetic in the following way:
- Start the ROS node mavros apm.launch with fcu_url
udp://:14550@127.0.0.1:14555and gcs_urludp://:14550@127.0.0.1:14558 - Start QGroundControl.
This setup worked for me to control the BlueROV2 via QGroundControl and at the same time send messages via mavros. For example, I use the rosservice /mavros/cmd/command to control a servo with the command MAV_CMD_SET_SERVO (full mavros cmd list).
rosservice call /mavros/cmd/command 0 183 1 9 1500 0 0 0 0 0
This sets the servo at channel 9 to PWM value 1500.
Example skeleton code to call the service with Python:
import rospy
from mavros_msgs.srv import CommandLong
# command code (see link above)
MAV_CMD_SET_SERVO = 183
# servo channel - "9" should be the lights in the standard BlueROV setup
CHANNEL = 9
# PWM value - for the lights, 500 is dim and 2500 is very bright
VALUE = 1500
# this needs to be set up once
mavcmd_proxy = rospy.ServiceProxy("/mavros/cmd/command", CommandLong)
# this needs to be called every time you want to change the PWM value
# all the "0" are parameter slots that can be set for other commands but are not required in this case
response = mavcmd_proxy(0, MAV_CMD_SET_SERVO, 0, CHANNEL, VALUE, 0, 0, 0, 0, 0)