You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
My goal is to write a ROS2 node that can command an IRL drone to move forward and backwards using:
CubeOrangePlus as the FCU
Raspberry Pi 4B as an onboard computer.
I'm opening this issue in the hopes of providing some info for anyone coming across the same problems as me and asking for any tips on unsolved errors I have encountered.
The connection was made successfully and all the topics were listed, however at first, all of them were "silent," there wasn't anything published on them except the "/mavros/state" and the "/diagnostics".
This was fixed by setting the SR0_XXX parameters to 10Hz on the Cube. After that, all sensor data was streaming as expected.
After reading this issue #1718 I managed to make some things work (Thanks for the users for sharing their findings):
I can change Flight Modes using this command: ros2 service call /mavros/set_mode mavros_msgs/srv/SetMode "{base_mode: 0, custom_mode: 'GUIDED_NOGPS'}"
And I can also ARM and DISARM the drone using this command: ros2 service call /mavros/cmd/arming mavros_msgs/srv/CommandBool "{value: True}"
When I try to send the TAKEOFF command using: ros2 service call /mavros/cmd/takeoff mavros_msgs/srv/CommandTOL "{min_pitch: 0, yaw: 0, altitude: 30}"
MavRos console returns success with (result: 0), however, nothing happens IRL, but when the altitude value is increased to 40, it starts returning (result: 4), which is a "Command Denied" error:
rosservice call /mavros/cmd/takeoff mavros_msgs/srv/CommandTOL "{min_pitch: 0, yaw: 0, altitude: 40}"
waiting for service to become available...
requester: making request: mavros_msgs.srv.CommandTOL_Request(min_pitch=0.0, yaw=0.0, latitude=0.0, longitude=0.0, altitude=40.0)
response:
mavros_msgs.srv.CommandTOL_Response(success=False, result=4)
What I gathered so far is:
I have a good connection to the drone.
I can read data from the drone.
I can send some commands to the drone.
However, the real problem starts when I try to send commands using topics:
I am unable to command the drone motors. It's like the drone is in "read-only" mode, as I can listen to any of the topics, but anything I try to publish falls on deaf ears.
I have tried publishing (on the following topics) without result. (I set the RC_OPTIONS parameter to enable override):
I've read that there was an "OFFBOARD" flight mode for exactly this purpose, however, it's deprecated in Ardupilot 4.5.
I also tried it in ALTHOLD and GUIDED_NOGPS, unsuccessfully.
My main questions are:
Am I using the wrong topics to send movement commands?
Is there an Ardupilot parameter I haven't mentioned that is preventing the commands from being executed?
About the Documentation
I saw many people ask already, but it would be massively helpful if we could get some up to date documentation about the current state of ROS2 and MavRos.
Every offical post is outdated or vague. I wasn't able to find anything specifically for ROS2, any examples, or description.
These systems have all the potential in the world, but they are currently unusable for new developers trying to enter.
Please feel free the lecture me if I got anything wrong or I missed something.
Thank you.
Nodes:
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import TwistStamped
class MotorTestNode(Node):
def __init__(self):
super().__init__('motor_test')
self.publisher = self.create_publisher(TwistStamped, '/mavros/setpoint_velocity/cmd_vel', 10)
self.timer = self.create_timer(0.05, self.send_velocity_command)
self.get_logger().info('Velocity control node started')
def send_velocity_command(self):
msg = TwistStamped()
msg.header.stamp = self.get_clock().now().to_msg()
# Set velocity values
msg.twist.linear.x = 0.5 # Forward/backward velocity (m/s)
msg.twist.linear.y = 0.0 # Left/right velocity (m/s)
msg.twist.linear.z = 0.0 # Up/down velocity (m/s)
msg.twist.angular.x = 0.0 # Not used
msg.twist.angular.y = 0.0 # Not used
msg.twist.angular.z = 0.1 # Yaw rate (rad/s)
self.publisher.publish(msg)
self.get_logger().info('Publishing velocity command')
def main(args=None):
rclpy.init(args=args)
node = MotorTestNode()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
import rclpy
from rclpy.node import Node
from mavros_msgs.msg import OverrideRCIn
class RCOverrideNode(Node):
def __init__(self):
super().__init__('rc_override')
self.publisher = self.create_publisher(OverrideRCIn, '/mavros/rc/override', 10)
self.timer = self.create_timer(0.1, self.send_rc_override_command)
self.get_logger().info('RC Override node started')
def send_rc_override_command(self):
msg = OverrideRCIn()
msg.channels = [
1600, # Channel 1 (roll) - slightly right
1500, # Channel 2 (pitch) - neutral
1400, # Channel 3 (throttle) - slightly reduced throttle
1500, # Channel 4 (yaw) - neutral
65535, # Channel 5 - no override
65535, # Channel 6 - no override
65535, # Channel 7 - no override
65535, # Channel 8 - no override
65535, # Channel 9 - no override
65535, # Channel 10 - no override
65535, # Channel 11 - no override
65535, # Channel 12 - no override
65535, # Channel 13 - no override
65535, # Channel 14 - no override
65535, # Channel 15 - no override
65535, # Channel 16 - no override
65535, # Channel 17 - no override
65535 # Channel 18 - no override
]
self.publisher.publish(msg)
self.get_logger().info('Publishing RC override command')
def main(args=None):
rclpy.init(args=args)
node = RCOverrideNode()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
header:
stamp:
sec: 1726225927
nanosec: 246041410
frame_id: ''
status:
- level: "\0"
name: 'mavros: MAVROS UAS'
message: connected
hardware_id: uas:///uas1
values: []
- level: "\x02"
name: 'mavros: GPS'
message: No satellites
hardware_id: uas:///uas1
values:
- key: Satellites visible
value: '0'
- key: Fix type
value: '1'
- key: EPH (m)
value: '0.00'
- key: EPV (m)
value: '0.00'
- level: "\x01"
name: 'mavros: Mount'
message: Can not diagnose in this targeting mode
hardware_id: uas:///uas1
values:
- key: Mode
value: '255'
- level: "\0"
name: 'mavros: System'
message: Normal
hardware_id: uas:///uas1
values:
- key: Sensor present
value: '0x5361FD2F'
- key: Sensor enabled
value: '0x4361BD2F'
- key: Sensor health
value: '0x4771BD2F'
- key: 3D gyro
value: Ok
- key: 3D accelerometer
value: Ok
- key: 3D magnetometer
value: Ok
- key: absolute pressure
value: Ok
- key: GPS
value: Ok
- key: laser based position
value: Ok
- key: 3D angular rate control
value: Ok
- key: attitude stabilization
value: Ok
- key: yaw position
value: Ok
- key: z/altitude control
value: Ok
- key: motor outputs / control
value: Ok
- key: rc receiver
value: Ok
- key: AHRS subsystem health
value: Ok
- key: Terrain subsystem health
value: Ok
- key: Logging
value: Ok
- key: Battery
value: Ok
- key: propulsion (actuator, esc, motor or propellor)
value: Ok
- key: CPU Load (%)
value: '30.1'
- key: Drop rate (%)
value: '0.0'
- key: Errors comm
value: '0'
- key: 'Errors count #1'
value: '0'
- key: 'Errors count #2'
value: '0'
- key: 'Errors count #3'
value: '0'
- key: 'Errors count #4'
value: '0'
- level: "\0"
name: 'mavros: Battery'
message: Normal
hardware_id: uas:///uas1
values:
- key: Voltage
value: '49.94'
- key: Current
value: '-0.4'
- key: Remaining
value: '21.0'
- level: "\0"
name: 'mavros: Heartbeat'
message: Normal
hardware_id: uas:///uas1
values:
- key: Heartbeats since startup
value: '44'
- key: Frequency (Hz)
value: '1.000051'
- key: Vehicle type
value: Quadrotor
- key: Autopilot type
value: ArduPilot
- key: Mode
value: GUIDED_NOGPS
- key: System status
value: STANDBY
The text was updated successfully, but these errors were encountered:
Sadufy2
changed the title
ROS2 Quadcopter velocity control / RC Override / Topics and Services Documentation
ROS2 Quadcopter velocity control / RC Control Override / Topics and Services Documentation
Sep 13, 2024
Issue Details
My goal is to write a ROS2 node that can command an IRL drone to move forward and backwards using:
I'm opening this issue in the hopes of providing some info for anyone coming across the same problems as me and asking for any tips on unsolved errors I have encountered.
Using the Ardupilot documentation here (https://ardupilot.org/copter/docs/common-serial-options.html) I was able to,
After cloning the MAVROS source code to "ros2_ws/src" folder, I built the packages (it took around 50min).
Launch file:
The connection was made successfully and all the topics were listed, however at first, all of them were "silent," there wasn't anything published on them except the "/mavros/state" and the "/diagnostics".
This was fixed by setting the SR0_XXX parameters to 10Hz on the Cube. After that, all sensor data was streaming as expected.
After reading this issue #1718 I managed to make some things work (Thanks for the users for sharing their findings):
ros2 service call /mavros/set_mode mavros_msgs/srv/SetMode "{base_mode: 0, custom_mode: 'GUIDED_NOGPS'}"
ros2 service call /mavros/cmd/arming mavros_msgs/srv/CommandBool "{value: True}"
ros2 service call /mavros/cmd/takeoff mavros_msgs/srv/CommandTOL "{min_pitch: 0, yaw: 0, altitude: 30}"
MavRos console returns success with (result: 0), however, nothing happens IRL, but when the altitude value is increased to 40, it starts returning (result: 4), which is a "Command Denied" error:
What I gathered so far is:
However, the real problem starts when I try to send commands using topics:
My main questions are:
About the Documentation
I saw many people ask already, but it would be massively helpful if we could get some up to date documentation about the current state of ROS2 and MavRos.
Every offical post is outdated or vague. I wasn't able to find anything specifically for ROS2, any examples, or description.
These systems have all the potential in the world, but they are currently unusable for new developers trying to enter.
Please feel free the lecture me if I got anything wrong or I missed something.
Thank you.
Nodes:
MAVROS version and platform
Mavros: 2.8.0
ROS2: Humble
Ubuntu: 22.04.4
Autopilot type and version
[ X ] ArduPilot
[ ] PX4
Version: 4.5.2
Node logs
Diagnostics
The text was updated successfully, but these errors were encountered: