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

Define parameters for the frame names of the static transforms #1909

Merged
merged 2 commits into from
Oct 16, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions mavros/include/mavros/mavros_uas.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -570,6 +570,10 @@ class UAS : public rclcpp::Node

std::string uas_url;

std::string base_link_frame_id;
std::string odom_frame_id;
std::string map_frame_id;

StrV plugin_allowlist;
StrV plugin_denylist;

Expand Down
18 changes: 15 additions & 3 deletions mavros/src/lib/mavros_uas.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,9 @@ UAS::UAS(
target_system(target_system_),
target_component(target_component_),
uas_url(uas_url_),
base_link_frame_id("base_link"),
odom_frame_id("odom"),
map_frame_id("map"),
plugin_factory_loader("mavros", "mavros::plugin::PluginFactory"),
loaded_plugins{},
plugin_subscriptions{},
Expand Down Expand Up @@ -77,6 +80,9 @@ UAS::UAS(
this->declare_parameter("target_component_id", target_component);
this->declare_parameter("plugin_allowlist", plugin_allowlist);
this->declare_parameter("plugin_denylist", plugin_denylist);
this->declare_parameter("base_link_frame_id", base_link_frame_id);
this->declare_parameter("odom_frame_id", odom_frame_id);
this->declare_parameter("map_frame_id", map_frame_id);

// NOTE(vooon): we couldn't add_plugin() in constructor because it needs shared_from_this()
startup_delay_timer = this->create_wall_timer(
Expand All @@ -93,6 +99,9 @@ UAS::UAS(
this->get_parameter("target_component_id", tgt_component);
this->get_parameter("plugin_allowlist", plugin_allowlist);
this->get_parameter("plugin_denylist", plugin_denylist);
this->get_parameter("base_link_frame_id", base_link_frame_id);
this->get_parameter("odom_frame_id", odom_frame_id);
this->get_parameter("map_frame_id", map_frame_id);

exec_spin_thd = thread_ptr(
new std::thread(
Expand Down Expand Up @@ -151,21 +160,24 @@ UAS::UAS(

// Publish helper TFs used for frame transformation in the odometry plugin
{
std::string base_link_frd = base_link_frame_id+"_frd";
std::string odom_ned = odom_frame_id+"_ned";
std::string map_ned = map_frame_id+"_ned";
std::vector<geometry_msgs::msg::TransformStamped> transform_vector;
add_static_transform(
"map", "map_ned", Eigen::Affine3d(
map_frame_id, map_ned, Eigen::Affine3d(
ftf::quaternion_from_rpy(
M_PI, 0,
M_PI_2)),
transform_vector);
add_static_transform(
"odom", "odom_ned", Eigen::Affine3d(
odom_frame_id, odom_ned, Eigen::Affine3d(
ftf::quaternion_from_rpy(
M_PI, 0,
M_PI_2)),
transform_vector);
add_static_transform(
"base_link", "base_link_frd",
base_link_frame_id, base_link_frd,
Eigen::Affine3d(ftf::quaternion_from_rpy(M_PI, 0, 0)), transform_vector);

tf2_static_broadcaster.sendTransform(transform_vector);
Expand Down
25 changes: 25 additions & 0 deletions mavros/src/mavros_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ int main(int argc, char * argv[])
// options.use_intra_process_comms(true);

std::string fcu_url, gcs_url, uas_url;
std::string base_link_frame_id, odom_frame_id, map_frame_id;
int tgt_system = 1, tgt_component = 1;

auto node = std::make_shared<rclcpp::Node>("mavros_node", options);
Expand All @@ -41,11 +42,17 @@ int main(int argc, char * argv[])
node->declare_parameter("gcs_url", gcs_url);
node->declare_parameter("tgt_system", tgt_system);
node->declare_parameter("tgt_component", tgt_component);
node->declare_parameter("base_link_frame", base_link_frame_id);
node->declare_parameter("map_frame", map_frame_id);
node->declare_parameter("odom_frame", odom_frame_id);

node->get_parameter("fcu_url", fcu_url);
node->get_parameter("gcs_url", gcs_url);
node->get_parameter("tgt_system", tgt_system);
node->get_parameter("tgt_component", tgt_component);
node->get_parameter("base_link_frame", base_link_frame_id);
node->get_parameter("map_frame", map_frame_id);
node->get_parameter("odom_frame", odom_frame_id);

uas_url = mavros::utils::format("/uas%d", tgt_system);

Expand Down Expand Up @@ -78,6 +85,24 @@ int main(int argc, char * argv[])
tgt_component);
exec.add_node(uas_node);

{
std::vector<rclcpp::Parameter> uas_params{};

if (base_link_frame_id != "") {
uas_params.emplace_back("base_link_frame_id", base_link_frame_id);
}

if (odom_frame_id != "") {
uas_params.emplace_back("odom_frame_id", odom_frame_id);
}

if (map_frame_id != "") {
uas_params.emplace_back("map_frame_id", map_frame_id);
}
uas_node->set_parameters(uas_params);

}

exec.spin();
rclcpp::shutdown();
return 0;
Expand Down
8 changes: 4 additions & 4 deletions mavros_extras/src/plugins/odom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,8 +144,8 @@ class OdometryPlugin : public plugin::Plugin
Eigen::Affine3d tf_parent2parent_des;
Eigen::Affine3d tf_child2child_des;

lookup_static_transform(fcu_odom_parent_id_des, "map_ned", tf_parent2parent_des);
lookup_static_transform(fcu_odom_child_id_des, "base_link_frd", tf_child2child_des);
lookup_static_transform(fcu_odom_parent_id_des, fcu_odom_parent_id_des+"_ned", tf_parent2parent_des);
lookup_static_transform(fcu_odom_child_id_des, fcu_odom_child_id_des+"_frd", tf_child2child_des);

//! Build 6x6 pose covariance matrix to be transformed and sent
Matrix6d cov_pose = Matrix6d::Zero();
Expand Down Expand Up @@ -235,8 +235,8 @@ class OdometryPlugin : public plugin::Plugin
Eigen::Affine3d tf_parent2parent_des;
Eigen::Affine3d tf_child2child_des;

lookup_static_transform("odom_ned", odom->header.frame_id, tf_parent2parent_des);
lookup_static_transform("base_link_frd", odom->child_frame_id, tf_child2child_des);
lookup_static_transform(odom->header.frame_id+"_ned", odom->header.frame_id, tf_parent2parent_des);
lookup_static_transform(odom->child_frame_id+"_frd", odom->child_frame_id, tf_child2child_des);

//! Build 6x6 pose covariance matrix to be transformed and sent
ftf::Covariance6d cov_pose = odom->pose.covariance;
Expand Down
Loading