Skip to content
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

fix px4 launch file for ROS2 #1834

Merged
merged 7 commits into from
Feb 24, 2023
Merged

fix px4 launch file for ROS2 #1834

merged 7 commits into from
Feb 24, 2023

Conversation

vacabun
Copy link
Contributor

@vacabun vacabun commented Feb 23, 2023

I modified px4 launch file for ROS2, and tested it in the simulation environment.

Copy link
Member

@vooon vooon left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Overally looks good. Can you please do the same for apm?

laser_1_sub:
subscriber: true
id: 3
orientation: PITCH_270
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That plugin now parses yaml from string parameter.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, I see

@vacabun
Copy link
Contributor Author

vacabun commented Feb 24, 2023

OK, I will try to do the same for apm.

@vacabun
Copy link
Contributor Author

vacabun commented Feb 24, 2023

I don't find any use for event_launcher.yaml and mavlink_bridge.launch, should I remove them.

@vooon
Copy link
Member

vooon commented Feb 24, 2023

Yes, bridge is not needed anymore, because you have router.
And I've removed event_launcher as it should be done differently, like a plugin to launch system, or something like that.

@vooon vooon added this to the Version 2.5 milestone Feb 24, 2023
@vooon vooon added this to TODO in ROS2 support via automation Feb 24, 2023
@vooon
Copy link
Member

vooon commented Feb 24, 2023

Fix #1564
Replace #1747

@vacabun
Copy link
Contributor Author

vacabun commented Feb 24, 2023

OK,I have removed them.

Copy link
Member

@vooon vooon left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Have you tried to use this launch?
I just have an idea, that params file not fully loaded.

Do you know, is it possible to define namespace for params?
Just if you run several copies of the UAS to control few drones, it might be convenient to have same config.

send: false # send TF?
frame_id: "map" # TF frame_id
global_frame_id: "earth" # TF earth frame_id
child_frame_id: "base_link" # TF child_frame_id
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In ROS2 parameters are flat, so i had to change names. Please have a look:

// tf subsection
node_declare_and_watch_parameter(
"tf.send", false, [&](const rclcpp::Parameter & p) {
tf_send = p.as_bool();
});
node_declare_and_watch_parameter(
"tf.frame_id", "map", [&](const rclcpp::Parameter & p) {
tf_frame_id = p.as_string();
});
// The global_origin should be represented as "earth" coordinate frame (ECEF) (REP 105)
node_declare_and_watch_parameter(
"tf.global_frame_id", "earth", [&](const rclcpp::Parameter & p) {
tf_global_frame_id = p.as_string();
});
node_declare_and_watch_parameter(
"tf.child_frame_id", "base_link", [&](const rclcpp::Parameter & p) {
tf_child_frame_id = p.as_string();
});

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, I see.

p1: {x: 1.0, y: 1.0, z: 1.0}
p2: {x: -1.0, y: -1.0, z: -1.0}
# # safety_area
/mavros/safety_area:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Safety area is quite deprecated feature. I've removed it from ROS2.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, I see.

orientation: PITCH_270
/mavros/distance_sensor:
ros__parameters:
config: |
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, that's what i mean. +1

mocap_transform: true # ~mocap/tf instead of pose
use_vision: false # ~vision (pose)
# origin (default: Zürich)
geo_origin:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

node_declare_and_watch_parameter(
"geo_origin.lat", 47.3667, [&](const rclcpp::Parameter & p) {
map_origin.x() = p.as_double();
});
node_declare_and_watch_parameter(
"geo_origin.lon", 8.5500, [&](const rclcpp::Parameter & p) {
map_origin.y() = p.as_double();
});
node_declare_and_watch_parameter(
"geo_origin.alt", 408.0, [&](const rclcpp::Parameter & p) {
map_origin.z() = p.as_double();
});

So it should look like:

fake_gps:
  ros__parameters:
    geo_origin.lat: 47.3667

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, I see.

@vacabun
Copy link
Contributor Author

vacabun commented Feb 24, 2023

I have used this launch, but just tested a little.

I think is a good idea. That will be really convenient for using multiple drones.

@vacabun
Copy link
Contributor Author

vacabun commented Feb 24, 2023

The plugin odometry in apm launch has two parameters.

# odom
odometry:
frame_tf:
desired_frame: "ned"
estimator_type: 3 # check enum MAV_ESTIMATOR_TYPE in <https://mavlink.io/en/messages/common.html>

I can't find the parameters frame_tf.desired_frame and estimator_type in mavros_extras/src/plugins/odom.cpp.
Should I modify it as px4 launch.

odometry:
fcu:
odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
odom_child_id_des: "base_link" # desired child frame rotation of the FCU's odometry

Finally, it looks like:

# odom
/mavros/odometry:
  ros__parameters:
    fcu.odom_parent_id_des: "map"    # desired parent frame rotation of the FCU's odometry
    fcu.odom_child_id_des: "base_link"    # desired child frame rotation of the FCU's odometry

2.Remove plugin safety_area in launch parameters file.
@vooon
Copy link
Member

vooon commented Feb 24, 2023

Odom have changed a lot, so it's not a surprise that conf outdated.

We should use parameters what ROS2 have.

node_declare_and_watch_parameter(
"fcu.odom_parent_id_des", "map", [&](const rclcpp::Parameter & p) {
fcu_odom_parent_id_des = p.as_string();
});
node_declare_and_watch_parameter(
"fcu.odom_child_id_des", "map", [&](const rclcpp::Parameter & p) {
fcu_odom_child_id_des = p.as_string();
});

Copy link
Member

@vooon vooon left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM, Thanks!

ROS2 support automation moved this from TODO to In Progress Feb 24, 2023
@vooon
Copy link
Member

vooon commented Feb 24, 2023

Yes, in ROS2 i've implemented idea of splitting mavlink connections and UAS. So if previously you have to run several copies of whole mavros_node, and maybe gcs_nodes, now it utilizes ros2 loadable node classes.

FCU1 -> Router -> UAS1
FCU2 --^          &-> UAS2
                  &-> GCS

@vooon vooon merged commit ea55539 into mavlink:ros2 Feb 24, 2023
ROS2 support automation moved this from In Progress to Done Feb 24, 2023
@vooon vooon mentioned this pull request Feb 24, 2023
@vacabun vacabun deleted the px4_launch_fix branch February 24, 2023 11:38
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
ROS2 support
  
Done
Development

Successfully merging this pull request may close these issues.

None yet

2 participants