diff --git a/config/public/dummy/dummy.yaml b/config/public/dummy/dummy.yaml index f197478..e69de29 100644 --- a/config/public/dummy/dummy.yaml +++ b/config/public/dummy/dummy.yaml @@ -1,18 +0,0 @@ -mrs_uav_managers: - estimation_manager: - dummy: - max_flight_z: 100.0 # [m] maximum allowed flight Z (in the estimator frame) - - message: - topic: "" - - requires: # data required from the hw api - gnss: false - imu: false - distance_sensor: false - altitude: false - magnetometer_heading: false - position: false - orientation: false - velocity: false - angular_velocity: false diff --git a/src/estimators/state/dummy.cpp b/src/estimators/state/dummy.cpp index df40439..ad03303 100644 --- a/src/estimators/state/dummy.cpp +++ b/src/estimators/state/dummy.cpp @@ -18,6 +18,16 @@ void Dummy::initialize(ros::NodeHandle &nh, const std::shared_ptruav_name + "/" + frame_id_; + // | --------------- param loader initialization -------------- | + + ph->param_loader->addYamlFile(ros::package::getPath(package_name_) + "/config/private/" + getName() + "/" + getName() + ".yaml"); + ph->param_loader->addYamlFile(ros::package::getPath(package_name_) + "/config/public/" + getName() + "/" + getName() + ".yaml"); + + ph->param_loader->setPrefix(ch_->package_name + "/" + Support::toSnakeCase(ch_->nodelet_name) + "/" + getName() + "/"); + + // | --------------------- load parameters -------------------- | + ph->param_loader->loadParam("max_flight_z", max_flight_z_); + // | ------------------ timers initialization ----------------- | // timer_update_ = nh.createTimer(ros::Rate(ch_->desired_uav_state_rate), &Dummy::timerUpdate, this, false, false); // not running after init