diff --git a/mavros/launch/px4_config.yaml b/mavros/launch/px4_config.yaml index 6b2913c94..bb18b088f 100644 --- a/mavros/launch/px4_config.yaml +++ b/mavros/launch/px4_config.yaml @@ -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: diff --git a/mavros_extras/src/plugins/odom.cpp b/mavros_extras/src/plugins/odom.cpp index fed8b31be..44b8f4621 100644 --- a/mavros_extras/src/plugins/odom.cpp +++ b/mavros_extras/src/plugins/odom.cpp @@ -57,9 +57,9 @@ class OdometryPlugin : public plugin::PluginBase { PluginBase::initialize(uas_); // frame params: - odom_nh.param("fcu/odom_parent_id_des", fcu_map_id_des, uas_.get_map_frame_id()); + odom_nh.param("fcu/odom_parent_id_des", fcu_odom_parent_id_des, uas_.get_odom_frame_id()); odom_nh.param("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("fcu/map_id_des", fcu_map_id_des, uas_.get_map_frame_id()); // publishers odom_pub = odom_nh.advertise("in", 10);