Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/graph names and widths #384

Merged
merged 4 commits into from
Sep 1, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions rmf_traffic_editor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ set(gui_sources
gui/editor.cpp
gui/editor_model.cpp
gui/fiducial.cpp
gui/graph.cpp
gui/layer.cpp
gui/layer_dialog.cpp
gui/layer_table.cpp
Expand Down
17 changes: 16 additions & 1 deletion rmf_traffic_editor/gui/building.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,17 @@ bool Building::load(const string& _filename)
}
}

if (y["graphs"] && y["graphs"].IsMap())
{
const YAML::Node& g_map = y["graphs"];
for (YAML::const_iterator it = g_map.begin(); it != g_map.end(); ++it)
{
Graph graph;
graph.from_yaml(it->first.as<int>(), it->second);
graphs.push_back(graph);
}
}

calculate_all_transforms();
return true;
}
Expand Down Expand Up @@ -170,6 +181,10 @@ bool Building::save()
if (crowd_sim_impl)
y["crowd_sim"] = crowd_sim_impl->to_yaml();

y["graphs"] = YAML::Node(YAML::NodeType::Map);
for (const auto& graph : graphs)
y["graphs"][graph.idx] = graph.to_yaml();

YAML::Emitter emitter;
yaml_utils::write_node(y, emitter);
std::ofstream fout(filename);
Expand Down Expand Up @@ -694,7 +709,7 @@ void Building::draw(
return;
}

levels[level_idx].draw(scene, editor_models, rendering_options);
levels[level_idx].draw(scene, editor_models, rendering_options, graphs);
draw_lifts(scene, level_idx);
}

Expand Down
2 changes: 2 additions & 0 deletions rmf_traffic_editor/gui/building.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ class QGraphicsScene;
#include <QGraphicsLineItem>
#include <QPointF>

#include "graph.h"
#include "level.h"
#include "lift.h"
#include <traffic_editor/crowd_sim/crowd_sim_impl.h>
Expand All @@ -44,6 +45,7 @@ class Building
std::string reference_level_name;
std::vector<Level> levels;
std::vector<Lift> lifts;
std::vector<Graph> graphs;

mutable crowd_sim::CrowdSimImplPtr crowd_sim_impl;

Expand Down
51 changes: 51 additions & 0 deletions rmf_traffic_editor/gui/graph.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include "graph.h"
using std::string;

Graph::Graph()
{
}

Graph::~Graph()
{
}

bool Graph::from_yaml(const int _idx, const YAML::Node& data)
{
if (!data.IsMap())
throw std::runtime_error("Graph::from_yaml() expected a map");
idx = _idx;
//idx = std::stoi(idx_str);

if (data["name"])
name = data["name"].as<string>();

if (data["default_lane_width"])
default_lane_width = data["default_lane_width"].as<double>();

return true;
}

YAML::Node Graph::to_yaml() const
{
YAML::Node data;
data["name"] = name;
data["default_lane_width"] = default_lane_width;
return data;
}
39 changes: 39 additions & 0 deletions rmf_traffic_editor/gui/graph.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#ifndef TRAFFIC_EDITOR_GRAPH_H
#define TRAFFIC_EDITOR_GRAPH_H

#include <string>

#include <yaml-cpp/yaml.h>

class Graph
{
public:
Graph();
~Graph();

int idx = 0;
std::string name;
double default_lane_width = 1.0;

bool from_yaml(const int _idx, const YAML::Node& data);
YAML::Node to_yaml() const;
};

#endif
56 changes: 46 additions & 10 deletions rmf_traffic_editor/gui/level.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -616,7 +616,8 @@ void Level::calculate_scale()
void Level::draw_lane(
QGraphicsScene* scene,
const Edge& edge,
const RenderingOptions& opts) const
const RenderingOptions& opts,
const vector<Graph>& graphs) const
{
const int graph_idx = edge.get_graph_idx();
if (graph_idx >= 0 &&
Expand All @@ -630,8 +631,24 @@ void Level::draw_lane(
const double dy = v_end.y - v_start.y;
const double len = std::sqrt(dx*dx + dy*dy);

double pen_width_in_meters = edge.get_width() > 0 ? edge.get_width() : 1.0;
const double lane_pen_width = pen_width_in_meters / drawing_meters_per_pixel;
// see if there is a default width for this graph_idx
double graph_default_width = -1.0;
for (const auto& graph : graphs)
{
if (graph.idx == graph_idx)
{
graph_default_width = graph.default_lane_width;
break;
}
}

double lane_width_meters = 1.0;
if (edge.get_width() > 0)
lane_width_meters = edge.get_width();
else if (graph_default_width > 0)
lane_width_meters = graph_default_width;

const double lane_pen_width = lane_width_meters / drawing_meters_per_pixel;

const QPen arrow_pen(
QBrush(QColor::fromRgbF(0.0, 0.0, 0.0, 0.5)),
Expand Down Expand Up @@ -1073,7 +1090,8 @@ void Level::clear_selection()
void Level::draw(
QGraphicsScene* scene,
vector<EditorModel>& editor_models,
const RenderingOptions& rendering_options)
const RenderingOptions& rendering_options,
const vector<Graph>& graphs)
{
if (drawing_filename.size() && _drawing_visible)
{
Expand Down Expand Up @@ -1110,22 +1128,40 @@ void Level::draw(
{
switch (edge.type)
{
case Edge::LANE: draw_lane(scene, edge, rendering_options); break;
case Edge::WALL: draw_wall(scene, edge); break;
case Edge::MEAS: draw_meas(scene, edge); break;
case Edge::DOOR: draw_door(scene, edge); break;
case Edge::HUMAN_LANE: draw_lane(scene, edge, rendering_options); break;
case Edge::LANE:
draw_lane(scene, edge, rendering_options, graphs);
break;
case Edge::WALL:
draw_wall(scene, edge);
break;
case Edge::MEAS:
draw_meas(scene, edge);
break;
case Edge::DOOR:
draw_door(scene, edge);
break;
case Edge::HUMAN_LANE:
draw_lane(scene, edge, rendering_options, graphs);
break;
default:
printf("tried to draw unknown edge type: %d\n",
static_cast<int>(edge.type));
break;
}
}

QFont vertex_name_font("Helvetica");
double vertex_name_font_size =
vertex_radius / drawing_meters_per_pixel * 1.5;
if (vertex_name_font_size < 1.0)
vertex_name_font_size = 1.0;
vertex_name_font.setPointSizeF(vertex_name_font_size);

for (const auto& v : vertices)
v.draw(
scene,
vertex_radius / drawing_meters_per_pixel);
vertex_radius / drawing_meters_per_pixel,
vertex_name_font);

for (const auto& f : fiducials)
f.draw(scene, drawing_meters_per_pixel);
Expand Down
7 changes: 5 additions & 2 deletions rmf_traffic_editor/gui/level.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "editor_model.h"
#include "feature.hpp"
#include "fiducial.h"
#include "graph.h"
#include "layer.h"
#include "model.h"
#include "polygon.h"
Expand Down Expand Up @@ -161,7 +162,8 @@ class Level
void draw(
QGraphicsScene* scene,
std::vector<EditorModel>& editor_models,
const RenderingOptions& rendering_options);
const RenderingOptions& rendering_options,
const std::vector<Graph>& graphs);

void clear_scene();

Expand Down Expand Up @@ -203,7 +205,8 @@ class Level
void draw_lane(
QGraphicsScene* scene,
const Edge& edge,
const RenderingOptions& rendering_options) const;
const RenderingOptions& rendering_options,
const std::vector<Graph>& graphs) const;

void draw_wall(QGraphicsScene* scene, const Edge& edge) const;
void draw_meas(QGraphicsScene* scene, const Edge& edge) const;
Expand Down
7 changes: 4 additions & 3 deletions rmf_traffic_editor/gui/vertex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,8 @@ YAML::Node Vertex::to_yaml() const

void Vertex::draw(
QGraphicsScene* scene,
const double radius) const
const double radius,
const QFont& font) const
{
QPen vertex_pen(Qt::black);
vertex_pen.setWidthF(radius / 2.0);
Expand Down Expand Up @@ -240,9 +241,9 @@ void Vertex::draw(
{
QGraphicsSimpleTextItem* text_item = scene->addSimpleText(
QString::fromStdString(name),
QFont("Helvetica", 6));
font);
text_item->setBrush(selected ? selected_color : vertex_color);
text_item->setPos(x, y + radius);
text_item->setPos(x, y - 1 + radius);
}
}

Expand Down
3 changes: 2 additions & 1 deletion rmf_traffic_editor/gui/vertex.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,8 @@ class Vertex

void draw(
QGraphicsScene* scene,
const double radius) const;
const double radius,
const QFont& font) const;

bool is_parking_point() const;
bool is_holding_point() const;
Expand Down