Skip to content

Commit

Permalink
add param to odom plugin
Browse files Browse the repository at this point in the history
  • Loading branch information
EnderMandS committed Jul 15, 2024
1 parent 6067ce6 commit e2c04b5
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
3 changes: 2 additions & 1 deletion mavros/launch/px4_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -231,8 +231,9 @@ mount:
# odom
odometry:
fcu:
odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
odom_parent_id_des: "odom" # desired parent frame rotation of the FCU's odometry
odom_child_id_des: "base_link" # desired child frame rotation of the FCU's odometry
map_id_des: "map"

# px4flow
px4flow:
Expand Down
4 changes: 2 additions & 2 deletions mavros_extras/src/plugins/odom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,9 +57,9 @@ class OdometryPlugin : public plugin::PluginBase {
PluginBase::initialize(uas_);

// frame params:
odom_nh.param<std::string>("fcu/odom_parent_id_des", fcu_map_id_des, uas_.get_map_frame_id());
odom_nh.param<std::string>("fcu/odom_parent_id_des", fcu_odom_parent_id_des, uas_.get_odom_frame_id());
odom_nh.param<std::string>("fcu/odom_child_id_des", fcu_odom_child_id_des, uas_.get_base_link_frame_id());
fcu_odom_parent_id_des = uas_.get_odom_frame_id();
odom_nh.param<std::string>("fcu/map_id_des", fcu_map_id_des, uas_.get_map_frame_id());

// publishers
odom_pub = odom_nh.advertise<nav_msgs::Odometry>("in", 10);
Expand Down

0 comments on commit e2c04b5

Please sign in to comment.