Skip to content

Commit a20c837

Browse files
committed
Merge branch 'master' into ros2
* master: 1.20.1 update changelog 1.20.0 update changelog update mavlink dep branch Add missing std_srvs dependency add param to odom plugin add frame_id parameter Fix compile error when compiling with gcc 13
2 parents 5ca7165 + 39d0929 commit a20c837

File tree

13 files changed

+103
-41
lines changed

13 files changed

+103
-41
lines changed

libmavconn/CHANGELOG.rst

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,12 @@ Changelog for package libmavconn
1616
* update changelog
1717
* Contributors: Vladimir Ermakov
1818

19+
1.20.1 (2025-05-05)
20+
-------------------
21+
22+
1.20.0 (2024-10-10)
23+
-------------------
24+
1925
1.19.0 (2024-06-06)
2026
-------------------
2127

mavros/CHANGELOG.rst

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,15 @@ Changelog for package mavros
5353
Fixed bug `#569 <https://github.com/mavlink/mavros/issues/569>`_ from mavros. Fixed another bug in the building of the ros mavlink message- the seq field was not added to the ros mavlink message.
5454
* Contributors: Beniamino Pozzan, Vladimir Ermakov, danielkalmanson
5555

56+
1.20.1 (2025-05-05)
57+
-------------------
58+
59+
1.20.0 (2024-10-10)
60+
-------------------
61+
* add param to odom plugin
62+
* add frame_id parameter
63+
* Contributors: EnderMandS
64+
5665
1.19.0 (2024-06-06)
5766
-------------------
5867
* gps_global_origin: remove LLA to ECEF conversion

mavros/include/mavros/mavros_uas.hpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -379,6 +379,28 @@ class UAS : public rclcpp::Node
379379
const std::string & frame_id, const std::string & child_id,
380380
const Eigen::Affine3d & tr);
381381

382+
inline void set_base_link_frame_id(const std::string frame_id) {
383+
base_link_frame_id = frame_id;
384+
}
385+
inline void set_odom_frame_id(const std::string frame_id) {
386+
odom_frame_id = frame_id;
387+
}
388+
inline void set_map_frame_id(const std::string frame_id) {
389+
map_frame_id = frame_id;
390+
}
391+
inline std::string get_base_link_frame_id() {
392+
return base_link_frame_id;
393+
}
394+
inline std::string get_odom_frame_id() {
395+
return odom_frame_id;
396+
}
397+
inline std::string get_map_frame_id() {
398+
return map_frame_id;
399+
}
400+
401+
//! Publish helper TFs used for frame transformation in the odometry plugin
402+
void setup_static_tf();
403+
382404
/* -*- time sync -*- */
383405

384406
inline void set_time_offset(uint64_t offset_ns)

mavros/launch/px4_config.yaml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -244,8 +244,9 @@
244244
# odom
245245
/**/odometry:
246246
ros__parameters:
247-
fcu.odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
247+
fcu.odom_parent_id_des: "odom" # desired parent frame rotation of the FCU's odometry
248248
fcu.odom_child_id_des: "base_link" # desired child frame rotation of the FCU's odometry
249+
fcu.map_id_des: "map"
249250

250251
# px4flow
251252
/**/px4flow:

mavros/src/lib/mavros_uas.cpp

Lines changed: 1 addition & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -159,29 +159,7 @@ UAS::UAS(
159159
connect_to_router();
160160

161161
// Publish helper TFs used for frame transformation in the odometry plugin
162-
{
163-
std::string base_link_frd = base_link_frame_id + "_frd";
164-
std::string odom_ned = odom_frame_id + "_ned";
165-
std::string map_ned = map_frame_id + "_ned";
166-
std::vector<geometry_msgs::msg::TransformStamped> transform_vector;
167-
add_static_transform(
168-
map_frame_id, map_ned, Eigen::Affine3d(
169-
ftf::quaternion_from_rpy(
170-
M_PI, 0,
171-
M_PI_2)),
172-
transform_vector);
173-
add_static_transform(
174-
odom_frame_id, odom_ned, Eigen::Affine3d(
175-
ftf::quaternion_from_rpy(
176-
M_PI, 0,
177-
M_PI_2)),
178-
transform_vector);
179-
add_static_transform(
180-
base_link_frame_id, base_link_frd,
181-
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, 0)), transform_vector);
182-
183-
tf2_static_broadcaster.sendTransform(transform_vector);
184-
}
162+
setup_static_tf()
185163

186164
std::stringstream ss;
187165
for (auto & s : mavconn::MAVConnInterface::get_known_dialects()) {

mavros/src/lib/uas_data.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include "mavros/utils.hpp"
2121
#include "mavros/px4_custom_mode.hpp"
2222

23+
<<<<<<< HEAD
2324
using namespace mavros::uas; // NOLINT
2425

2526
std::once_flag Data::init_flag;

mavros/src/lib/uas_tf.cpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,3 +47,18 @@ void UAS::publish_static_transform(
4747

4848
tf2_static_broadcaster.sendTransform(static_transform_stamped);
4949
}
50+
51+
void UAS::setup_static_tf()
52+
{
53+
std::vector<geometry_msgs::TransformStamped> transform_vector;
54+
add_static_transform(map_frame_id, map_frame_id+"_ned",
55+
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, M_PI_2)),
56+
transform_vector);
57+
add_static_transform(odom_frame_id, odom_frame_id+"_ned",
58+
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, M_PI_2)),
59+
transform_vector);
60+
add_static_transform(base_link_frame_id, base_link_frame_id+"_frd",
61+
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, 0)),
62+
transform_vector);
63+
tf2_static_broadcaster.sendTransform(transform_vector);
64+
}

mavros_extras/CHANGELOG.rst

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,19 @@ Changelog for package mavros_extras
4141
Added all functionality to support a plugin to enable compatibility with MAVLink Gimbal Protocol v2
4242
* Contributors: Frederik Mazur Andersen, Mark-Beaty, Vladimir Ermakov
4343

44+
1.20.1 (2025-05-05)
45+
-------------------
46+
47+
1.20.0 (2024-10-10)
48+
-------------------
49+
* Add missing std_srvs dependency
50+
* add param to odom plugin
51+
* add frame_id parameter
52+
* Fix compile error when compiling with gcc 13
53+
The error is:
54+
src/plugins/mag_calibration_status.cpp:64:22: error: ‘bitset’ is not a member of ‘std’
55+
* Contributors: EnderMandS, Michal Sojka, Roland Arsenault
56+
4457
1.19.0 (2024-06-06)
4558
-------------------
4659

mavros_extras/src/plugins/odom.cpp

Lines changed: 17 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -57,20 +57,26 @@ class OdometryPlugin : public plugin::Plugin
5757

5858
explicit OdometryPlugin(plugin::UASPtr uas_)
5959
: Plugin(uas_, "odometry"),
60+
fcu_map_id_des("map"),
6061
fcu_odom_parent_id_des("map"),
6162
fcu_odom_child_id_des("base_link")
6263
{
6364
enable_node_watch_parameters();
6465

6566
// frame params:
6667
node_declare_and_watch_parameter(
67-
"fcu.odom_parent_id_des", "map", [&](const rclcpp::Parameter & p) {
68+
"fcu.odom_parent_id_des", uas_.get_odom_frame_id(), [&](const rclcpp::Parameter & p) {
6869
fcu_odom_parent_id_des = p.as_string();
6970
});
7071
node_declare_and_watch_parameter(
71-
"fcu.odom_child_id_des", "base_link", [&](const rclcpp::Parameter & p) {
72+
"fcu.odom_child_id_des", uas_.get_base_link_frame_id(), [&](const rclcpp::Parameter & p) {
7273
fcu_odom_child_id_des = p.as_string();
7374
});
75+
node_declare_and_watch_parameter(
76+
"fcu.map_id_des", uas_.get_map_frame_id(), [&](const rclcpp::Parameter & p) {
77+
fcu_map_id_des = p.as_string();
78+
});
79+
7480

7581
// publishers
7682
odom_pub = node->create_publisher<nav_msgs::msg::Odometry>("~/in", 10);
@@ -93,10 +99,9 @@ class OdometryPlugin : public plugin::Plugin
9399
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_pub;
94100
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub;
95101

96-
//!< desired orientation of the fcu odometry message's parent frame
97-
std::string fcu_odom_parent_id_des;
98-
//!< desired orientation of the fcu odometry message's child frame
99-
std::string fcu_odom_child_id_des;
102+
std::string fcu_odom_parent_id_des; //!< desired orientation of the fcu odometry message's parent frame
103+
std::string fcu_odom_child_id_des; //!< desired orientation of the fcu odometry message's child frame
104+
std::string fcu_map_id_des; //!< desired orientation of the fcu map frame
100105

101106
/**
102107
* @brief Lookup static transform with error handling
@@ -144,12 +149,12 @@ class OdometryPlugin : public plugin::Plugin
144149
Eigen::Affine3d tf_parent2parent_des;
145150
Eigen::Affine3d tf_child2child_des;
146151

147-
lookup_static_transform(
148-
fcu_odom_parent_id_des, fcu_odom_parent_id_des + "_ned",
149-
tf_parent2parent_des);
150-
lookup_static_transform(
151-
fcu_odom_child_id_des, fcu_odom_child_id_des + "_frd",
152-
tf_child2child_des);
152+
lookup_static_transform(
153+
fcu_map_id_des, fcu_map_id_des+"_ned",
154+
tf_parent2parent_des);
155+
lookup_static_transform(
156+
fcu_odom_child_id_des, fcu_odom_child_id_des+"_frd",
157+
tf_child2child_des);
153158

154159
//! Build 6x6 pose covariance matrix to be transformed and sent
155160
Matrix6d cov_pose = Matrix6d::Zero();

mavros_extras/src/plugins/wheel_odometry.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -98,12 +98,12 @@ class WheelOdometryPlugin : public plugin::Plugin
9898
});
9999

100100
node_declare_and_watch_parameter(
101-
"frame_id", "odom", [&](const rclcpp::Parameter & p) {
101+
"frame_id", uas_.get_odom_frame_id(), [&](const rclcpp::Parameter & p) {
102102
frame_id = p.as_string();
103103
});
104104

105105
node_declare_and_watch_parameter(
106-
"child_frame_id", "base_link", [&](const rclcpp::Parameter & p) {
106+
"child_frame_id", uas_.get_base_link_frame_id(), [&](const rclcpp::Parameter & p) {
107107
frame_id = p.as_string();
108108
});
109109

@@ -115,12 +115,12 @@ class WheelOdometryPlugin : public plugin::Plugin
115115

116116
// TF subsection
117117
node_declare_and_watch_parameter(
118-
"tf.frame_id", "odom", [&](const rclcpp::Parameter & p) {
118+
"tf.frame_id", uas_.get_odom_frame_id(), [&](const rclcpp::Parameter & p) {
119119
tf_frame_id = p.as_string();
120120
});
121121

122122
node_declare_and_watch_parameter(
123-
"tf.child_frame_id", "base_link", [&](const rclcpp::Parameter & p) {
123+
"tf.child_frame_id", uas_.get_base_link_frame_id(), [&](const rclcpp::Parameter & p) {
124124
tf_child_frame_id = p.as_string();
125125
});
126126

0 commit comments

Comments
 (0)