Skip to content

Commit a0dad81

Browse files
Feature/better saving (#24)
* manually save in hydra node * update to latest hydra changes * drop unused file
1 parent 42867ab commit a0dad81

File tree

5 files changed

+10
-104
lines changed

5 files changed

+10
-104
lines changed

hydra_ros/app/hydra_node.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535
#include <config_utilities/config_utilities.h>
3636
#include <config_utilities/external_registry.h>
3737
#include <config_utilities/formatting/asl.h>
38+
#include <config_utilities/types/path.h>
3839
#include <config_utilities/logging/log_to_glog.h>
3940
#include <config_utilities/parsing/context.h>
4041
#include <hydra/common/global_info.h>
@@ -60,6 +61,8 @@ struct RunSettings {
6061
bool forward_glog_to_ros = true;
6162
int glog_level = 0;
6263
int glog_verbosity = 0;
64+
std::filesystem::path log_path;
65+
hydra::DataDirectory::Config output;
6366
};
6467

6568
void declare_config(RunSettings& config) {
@@ -79,6 +82,8 @@ void declare_config(RunSettings& config) {
7982
field(config.forward_glog_to_ros, "forward_glog_to_ros");
8083
field(config.glog_level, "glog_level");
8184
field(config.glog_verbosity, "glog_verbosity");
85+
field<Path::Absolute>(config.log_path, "log_path");
86+
field(config.output, "output");
8287
}
8388

8489
struct RosSink : google::LogSink {
@@ -158,9 +163,9 @@ int main(int argc, char* argv[]) {
158163
hydra.start();
159164
ianvs::spinAndWait(nh, settings.exit_after_clock);
160165
hydra.stop();
161-
hydra.save();
162-
// TODO(nathan) save full config
163-
hydra::GlobalInfo::exit();
166+
167+
const hydra::DataDirectory output(settings.log_path, settings.output);
168+
hydra.save(output);
164169
} // end hydra scope
165170

166171
if (ros_sink) {

hydra_ros/include/hydra_ros/input/feature_receiver.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,6 @@ class FeatureReceiver : public Module {
6060
virtual ~FeatureReceiver();
6161
void start() override;
6262
void stop() override;
63-
void save(const LogSetup& setup) override;
6463
std::string printInfo() const override;
6564

6665
private:

hydra_ros/scripts/copy_static_tfs.py

Lines changed: 0 additions & 95 deletions
This file was deleted.

hydra_ros/src/hydra_ros_pipeline.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -85,13 +85,12 @@ HydraRosPipeline::~HydraRosPipeline() {}
8585

8686
void HydraRosPipeline::init() {
8787
const auto& pipeline_config = GlobalInfo::instance().getConfig();
88-
const auto logs = GlobalInfo::instance().getLogs();
8988

9089
auto nh = getHydraNodeHandle("~");
91-
backend_ = config.backend.create(backend_dsg_, shared_state_, logs);
90+
backend_ = config.backend.create(backend_dsg_, shared_state_);
9291
modules_["backend"] = CHECK_NOTNULL(backend_);
9392

94-
frontend_ = config.frontend.create(frontend_dsg_, shared_state_, logs);
93+
frontend_ = config.frontend.create(frontend_dsg_, shared_state_);
9594
modules_["frontend"] = CHECK_NOTNULL(frontend_);
9695

9796
active_window_ = config.active_window.create(frontend_->queue());

hydra_ros/src/input/feature_receiver.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -133,8 +133,6 @@ FeatureReceiver::~FeatureReceiver() {}
133133

134134
void FeatureReceiver::stop() {}
135135

136-
void FeatureReceiver::save(const LogSetup&) {}
137-
138136
std::string FeatureReceiver::printInfo() const { return config::toString(config); }
139137

140138
} // namespace hydra

0 commit comments

Comments
 (0)