-
Notifications
You must be signed in to change notification settings - Fork 1k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Question: ros2 topic info /mavros/setpoint_velocity/cmd_vel(_unstamped) - Ardupilot Mode? #1870
Comments
Hi, Since all setpoint_foo uses |
Hey @vooon Thanks for the feedback. That is what I expected. Now when calling
I will get info:
which tells me I am in guided mode hence
which according to the message documentation on mavros_msgs/SetMode should be
and when sending
it responds with
Any suggestions? |
No, you literally should enable GUIDED mode, not guided-bit flag of base mode. I.e. custom_mode: "GUIDED". |
Additional information on Body Frames can be found here (ROS1): #792 Ok. So far:
To send some twist message, I again wrote some minimal example publisher, see:
and I will guess the
|
If i remember correctly plugin doesn't check frame_id. And i'm really unsure if Twist plugin has right type_mask for APM as it was initially developed for PX4. |
Additional information can be found here:
Based on your suggestion I worked on
messages. With the
which I believe will be binary
while in
which does not work. :( Weird little details that might help: When publishing those messages in |
Hello, As i remember, you should start publishing setpoints and then switch to GUIDED. |
Hi, this is all fun and games, but this:
means you cannot establish a velocity "live-stream" the rover (drone) follows as a reference, unless I keep toggling mode. i.e.
What I've read about, too is
Well this is just disappointing, but thank you for the heads-up. |
Hi, as stated earlier, In Control Theory/Robotics terms read this robotics.stackexchange question on difference path/trajectory planning:
but none of them are made for my intention: reference tracking. The closest implementation to reference tracking seems to be the My solution: The standard way to give commands to a robot in ROS is using a Twist Message, as e.g. Teleop Twist Keyboard in the early turtlebot tutorials or in NAV2. To now follow the twist message as a reference, I implemented a Node that subscribes any Twist message (topic Be aware this code is rather specific to your situation, as it depends on parameters set in Ardupilot and your robot. Those are:
The node "translating" Twist to RCOverride:
which works just fine, hence I will close the issue. But be aware: the solution is not ideal, my hope is that there is a closed control loop on the robot that somehow digests the RC-channels to references in velocity, otherwise it's open loop. To know, one would need to dig through the Ardupilot code. Thanks @vooon :) |
Issue details
I would like to control the robot in MAVROS2 using geometry_msgs/msg/Twist, since it is the "standard" interface to control a robot in ROS2, see e.g.
Expected behavior:
After running the Mavros node (Details, see below) and then publishing Twist-Messages into different topics:
which answers with
which answers with
which answers with:
The robot should start moving. Question:
What mode should be Ardupilot be in? GUIDED? MANUAL? What about the
frame_id
?MAVROS version and platform
Mavros: 2.5.0, installed from source
ROS2: Foxy
Ubuntu: 20.04. LTS
Autopilot type and version
[X] ArduPilot
[ ] PX4
Version: 4.2.3. Ardurover
Details
with
mavros_param.yaml
:ros2 run mavros mav checkid
returnsRouter topic: /uas1/mavlink_source, target: 1.1
Diagnostics
ros2 topic echo /diagnostics
:and Sink
ros2 topic echo /uas1/mavlink_source
:ROS2 Services and Topics
ros2 topic list:
ros2 service list:
The text was updated successfully, but these errors were encountered: