Skip to content

Commit

Permalink
refactor to completely outsource network transfer capability to trans…
Browse files Browse the repository at this point in the history
…folder
  • Loading branch information
mfehr committed Dec 6, 2019
1 parent 8ac214f commit cdc3728
Show file tree
Hide file tree
Showing 12 changed files with 126 additions and 422 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -7,63 +7,24 @@
#include <aslam/common/yaml-file-serialization.h>
#include <aslam/common/yaml-serialization.h>

DECLARE_string(maplab_server_merged_map_folder);
DECLARE_string(maplab_server_resource_folder);
DECLARE_int32(maplab_server_backup_interval_s);

namespace maplab {

class MaplabServerNodeConfig : public aslam::YamlFileSerializable {
public:
// Server config:
// Where the finished/intermediate maps should be stored. Not optional.
std::string map_folder = "";

// If empty, the standard map resource folder is used.
std::string resource_folder = "";

// Create a backup of the current map every n seconds. 0 = no backups.
size_t map_backup_interval_s = 0u;

std::vector<std::string> submap_commands;
std::vector<std::string> global_map_commands;

bool deserialize(const YAML::Node& config_node) override;
void serialize(YAML::Node* config_node_ptr) const override;

const std::string kYamlFieldNameMapFolder = "map_folder";
const std::string kYamlFieldNameResourceFolder = "resource_folder";
const std::string kYamlFieldNameBackupInterval = "map_backup_interval_s";

const std::string kYamlFieldNameSubmapCommands = "submap_commands";
const std::string kYamlFieldNameGlobalMapCommands = "global_map_commands";
};

struct RobotConnectionConfig {
std::string name;

// Topic on which map updates and locations are published.
std::string topic;

// Login info to transfer maps from the robot.
std::string ip;
std::string user;
};

struct MaplabServerRosNodeConfig : public aslam::YamlFileSerializable {
MaplabServerNodeConfig server_config;

// Robot fleet config:
std::vector<RobotConnectionConfig> connection_config;

bool deserialize(const YAML::Node& config_node) override;
void serialize(YAML::Node* config_node_ptr) const override;

const std::string kYamlFieldNameServerConfig = "server_config";

const std::string kYamlFieldNameRobotFleet = "connection_config";
const std::string kYamlFieldNameRobotName = "name";
const std::string kYamlFieldNameRobotIp = "ip";
const std::string kYamlFieldNameRobotTopic = "topic";
const std::string kYamlFieldNameRobotUser = "user";
};

} // namespace maplab

#endif // MAPLAB_SERVER_NODE_MAPLAB_SERVER_CONFIG_H_
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@ class MaplabServerNode final {

bool loadAndProcessSubmap(
const std::string& robot_name, const std::string& submap_path);
bool loadAndProcessSubmap(const std::string& submap_path);

// Save the map to disk.
bool saveMap(const std::string& path);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <string>
#include <vector>

#include <diagnostic_msgs/KeyValue.h>
#include <maplab_msgs/BatchMapLookup.h>
#include <ros/ros.h>
#include <std_msgs/String.h>
Expand All @@ -20,14 +21,12 @@ class MaplabServerRosNode {
const ros::NodeHandle& nh, const ros::NodeHandle& nh_private);

// Only for test purposes.
explicit MaplabServerRosNode(const MaplabServerRosNodeConfig& config);
explicit MaplabServerRosNode(const MaplabServerNodeConfig& config);

// Start the app.
bool start();

void submapLoadingCallback(
const std_msgs::StringConstPtr& msg,
const RobotConnectionConfig& robot_config);
void submapLoadingCallback(const diagnostic_msgs::KeyValueConstPtr& msg);

// Save current map.
bool saveMap(const std::string& map_folder);
Expand All @@ -47,8 +46,6 @@ class MaplabServerRosNode {
void visualizeMap();

private:
MaplabServerRosNodeConfig config_;

// ROS stuff.
ros::NodeHandle nh_;
ros::NodeHandle nh_private_;
Expand All @@ -62,7 +59,7 @@ class MaplabServerRosNode {
// One node to rule them all.
std::unique_ptr<MaplabServerNode> maplab_server_node_;

std::vector<ros::Subscriber> map_update_notification_subs_;
ros::Subscriber map_update_notification_sub_;
};

} // namespace maplab
Expand Down
1 change: 1 addition & 0 deletions applications/maplab-server-node/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<buildtool_depend>catkin</buildtool_depend>

<depend>aslam_cv_common</depend>
<depend>diagnostic_msgs</depend>
<depend>gflags_catkin</depend>
<depend>glog_catkin</depend>
<depend>maplab_common</depend>
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,35 +1,8 @@
server_config:
map_folder: "/tmp/euroc/maplab_server_map"
resource_folder: ""
map_backup_interval_s: 300
submap_commands:
- "optvi --ba_num_iterations=20 --ba_enable_signal_handler=false"

submap_commands:
- "optvi --ba_num_iterations=20 --ba_enable_signal_handler=false"

global_map_commands:
- "aam"
- "lc"
- "optvi --ba_num_iterations 1 --ba_enable_signal_handler=false"
- "elq --vi_map_landmark_quality_min_observers=2"

connection_config:
- name: euroc_mh_1
topic: "/euroc_mh_1/maplab_node/map_update_notification"
ip: "localhost"
user: "mfehr"
- name: euroc_mh_2
topic: "/euroc_mh_2/maplab_node/map_update_notification"
ip: "localhost"
user: "mfehr"
- name: euroc_mh_3
topic: "/euroc_mh_3/maplab_node/map_update_notification"
ip: "localhost"
user: "mfehr"
- name: euroc_mh_4
topic: "/euroc_mh_4/maplab_node/map_update_notification"
ip: "localhost"
user: "mfehr"
- name: euroc_mh_5
topic: "/euroc_mh_5/maplab_node/map_update_notification"
ip: "localhost"
user: "mfehr"
global_map_commands:
- "aam --lc_mission_baseframe_min_inlier_ratio=0.05 --lc_min_inlier_ratio=0.05 --lc_min_inlier_count=5 --lc_ransac_pixel_sigma=3"
- "lc"
- "optvi --ba_num_iterations 1 --ba_enable_signal_handler=false"
- "elq --vi_map_landmark_quality_min_observers=2"
27 changes: 8 additions & 19 deletions applications/maplab-server-node/share/example-server-config.yaml
Original file line number Diff line number Diff line change
@@ -1,20 +1,9 @@
server_config:
map_folder: "/tmp/maplab_server_node/combined_map"
resource_folder: "/tmp/maplab_server_node/combined_map_resources"
map_backup_interval_s: 300
submap_commands:
- "lc"
- "optvi --ba_num_iterations=20 --ba_enable_signal_handler=false"

submap_commands:
- "lc"
- "optvi --ba_num_iterations=20 --ba_enable_signal_handler=false"

global_map_commands:
- "lc"
- "optvi --ba_num_iterations=3 --ba_enable_signal_handler=false"
- "elq --vi_map_landmark_quality_min_observers=2"
- "rbl"

connection_config:
- name: local_maplab_node
topic: "/maplab_node/map_update_notification"
ip: "localhost"
user: ""
global_map_commands:
- "lc"
- "optvi --ba_num_iterations=3 --ba_enable_signal_handler=false"
- "elq --vi_map_landmark_quality_min_observers=2"
- "rbl"
125 changes: 11 additions & 114 deletions applications/maplab-server-node/src/maplab-server-config.cc
Original file line number Diff line number Diff line change
@@ -1,110 +1,19 @@
#include "maplab-server-node/maplab-server-config.h"

namespace maplab {

bool MaplabServerRosNodeConfig::deserialize(const YAML::Node& config_node) {
if (!config_node.IsDefined() || config_node.IsNull()) {
LOG(ERROR) << "Invalid YAML node for maplab server config deserialization.";
return false;
}

if (!config_node.IsMap()) {
LOG(WARNING) << "Maplab server config YAML node must be a map.";
return false;
}
DEFINE_string(
maplab_server_merged_map_folder, "",
"Where the finished/intermediate maps should be stored. Not optional.");

const YAML::Node& server_config_node =
config_node[kYamlFieldNameServerConfig];
server_config.deserialize(server_config_node);
DEFINE_string(
maplab_server_resource_folder, "",
"Where the resources of the merged map should be stored, if empty, the "
"standard map resource folder is used.");

// Parse the robot fleet config.
const YAML::Node& robot_fleet_node = config_node[kYamlFieldNameRobotFleet];
if (!robot_fleet_node.IsDefined() || robot_fleet_node.IsNull()) {
LOG(ERROR) << "Invalid maplab server config YAML. Can not parse robot "
<< "fleet config, since the '" << kYamlFieldNameRobotFleet
<< "' field is missing!";
return false;
}
DEFINE_int32(
maplab_server_backup_interval_s, 300,
"Create a backup of the current map every n seconds. 0 = no backups.");

if (!robot_fleet_node.IsSequence()) {
LOG(ERROR) << "Invalid maplab server config YAML. Can not parse robot "
<< "fleet config, since the '" << kYamlFieldNameRobotFleet
<< "' field is not a sequence!";
return false;
}
size_t num_robots = robot_fleet_node.size();
if (num_robots == 0) {
LOG(ERROR) << "Invalid maplab server config YAML. Can not parse robot "
<< "fleet config, since the '" << kYamlFieldNameRobotFleet
<< "' field does not contain any entries!";
return false;
}

for (size_t robot_index = 0; robot_index < num_robots; ++robot_index) {
// Decode the camera
const YAML::Node& robot_node = robot_fleet_node[robot_index];
if (!robot_node) {
LOG(ERROR) << "Unable to get YAML node for robot fleet config at index "
<< robot_index;
return false;
}

if (!robot_node.IsMap()) {
LOG(ERROR) << "YAML node for robot fleet config at index " << robot_index
<< " is not a map!";
return false;
}

RobotConnectionConfig robot_config;

if (YAML::safeGet(
robot_node, kYamlFieldNameRobotName, &robot_config.name)) {
CHECK(!robot_config.name.empty());
} else {
LOG(ERROR) << "YAML node for robot fleet config at index " << robot_index
<< " does not contain the '" << kYamlFieldNameRobotName
<< "' field!";
return false;
}

if (YAML::safeGet(robot_node, kYamlFieldNameRobotIp, &robot_config.ip)) {
CHECK(!robot_config.ip.empty());
} else {
LOG(ERROR) << "YAML node for robot fleet config at index " << robot_index
<< " does not contain the '" << kYamlFieldNameRobotIp
<< "' field!";
return false;
}

if (YAML::safeGet(
robot_node, kYamlFieldNameRobotTopic, &robot_config.topic)) {
CHECK(!robot_config.topic.empty());
} else {
LOG(ERROR) << "YAML node for robot fleet config at index " << robot_index
<< " does not contain the '" << kYamlFieldNameRobotTopic
<< "' field!";
return false;
}

if (YAML::safeGet(
robot_node, kYamlFieldNameRobotUser, &robot_config.user)) {
CHECK(!robot_config.user.empty());
} else {
LOG(ERROR) << "YAML node for robot fleet config at index " << robot_index
<< " does not contain the '" << kYamlFieldNameRobotUser
<< "' field!";
return false;
}

connection_config.push_back(robot_config);
}
return true;
}

void MaplabServerRosNodeConfig::serialize(
YAML::Node* /*config_node_ptr*/) const {
LOG(FATAL) << "Currently not implemented!";
}
namespace maplab {

bool MaplabServerNodeConfig::deserialize(const YAML::Node& config_node) {
if (!config_node.IsDefined() || config_node.IsNull()) {
Expand All @@ -117,18 +26,6 @@ bool MaplabServerNodeConfig::deserialize(const YAML::Node& config_node) {
return false;
}

if (YAML::safeGet(config_node, kYamlFieldNameMapFolder, &map_folder)) {
CHECK(!map_folder.empty());
} else {
LOG(WARNING) << "Maplab server config YAML needs a '"
<< kYamlFieldNameMapFolder << "' field!";
return false;
}

YAML::safeGet(config_node, kYamlFieldNameResourceFolder, &resource_folder);
YAML::safeGet(
config_node, kYamlFieldNameBackupInterval, &map_backup_interval_s);

// Parse submap and global map commands.
const YAML::Node& submap_commands_node =
config_node[kYamlFieldNameSubmapCommands];
Expand Down
Loading

0 comments on commit cdc3728

Please sign in to comment.