Skip to content

Commit

Permalink
fixed dummy estimator crashing
Browse files Browse the repository at this point in the history
  • Loading branch information
kratkvit committed Apr 15, 2024
1 parent 05ebc32 commit 0a64de6
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 18 deletions.
18 changes: 0 additions & 18 deletions config/public/dummy/dummy.yaml
Original file line number Diff line number Diff line change
@@ -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
10 changes: 10 additions & 0 deletions src/estimators/state/dummy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,16 @@ void Dummy::initialize(ros::NodeHandle &nh, const std::shared_ptr<CommonHandlers

ns_frame_id_ = ch_->uav_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
Expand Down

0 comments on commit 0a64de6

Please sign in to comment.