Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 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
10 changes: 10 additions & 0 deletions include/q_simulation_interfaces/service_discovery.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,10 @@ namespace q_simulation_interfaces
SERVICE_STEP_SIMULATION,
SERVICE_GET_SIM_STATE,
SERVICE_SET_SIM_STATE,
SERVICE_GET_CURRENT_WORLD,
SERVICE_GET_AVAILABLE_WORLDS,
SERVICE_LOAD_WORLD,
SERVICE_UNLOAD_WORLD,
ACTION_SIMULATE_STEPS,
SUPPORTED_SERVICE_IDL_COUNT
};
Expand Down Expand Up @@ -75,6 +79,12 @@ namespace q_simulation_interfaces
false},
{ServiceType::SERVICE_SET_SIM_STATE, "simulation_interfaces/srv/SetSimulationState", "Set Sim State",
false},
{ServiceType::SERVICE_GET_CURRENT_WORLD, "simulation_interfaces/srv/GetCurrentWorld", "Get Current World",
false},
{ServiceType::SERVICE_GET_AVAILABLE_WORLDS, "simulation_interfaces/srv/GetAvailableWorlds",
"Get Available Worlds", false},
{ServiceType::SERVICE_LOAD_WORLD, "simulation_interfaces/srv/LoadWorld", "Load World", false},
{ServiceType::SERVICE_UNLOAD_WORLD, "simulation_interfaces/srv/UnloadWorld", "Unload World", false},
{ServiceType::ACTION_SIMULATE_STEPS, "simulation_interfaces/action/SimulateSteps", "Simulate Steps",
true}}};

Expand Down
53 changes: 52 additions & 1 deletion src/sim_widget.ui
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
</rect>
</property>
<layout class="QFormLayout" name="formLayout">
<item row="0" column="0">
<item row="0" column="1">
<widget class="QTabWidget" name="tabWidget">
<property name="currentIndex">
<number>0</number>
Expand Down Expand Up @@ -519,6 +519,57 @@
</item>
</layout>
</widget>
<widget class="QWidget" name="worlds">
<attribute name="title">
<string>Worlds</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QPushButton" name="getAvailableWorldsButton">
<property name="text">
<string>Get Available Worlds</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="availableWorldsCombo"/>
</item>
<item>
<widget class="QPushButton" name="loadWorldButton">
<property name="text">
<string>Load World</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="unloadWorldButton">
<property name="text">
<string>Unload World</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="currentWorldLabel">
<property name="text">
<string>Current world:</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>225</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<widget class="QWidget" name="servicesNames">
<property name="enabled">
<bool>true</bool>
Expand Down
142 changes: 142 additions & 0 deletions src/simulation_widget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,9 @@ namespace q_simulation_interfaces
connect(ui_->setSimStateButton, &QPushButton::clicked, this, &SimulationWidget::SetSimulationState);
connect(ui_->stepSimServiceButton, &QPushButton::clicked, this, &SimulationWidget::StepSimulationService);
connect(ui_->ComboEntities, &QComboBox::currentTextChanged, this, [this]() { this->GetEntityState(true); });
connect(ui_->getAvailableWorldsButton, &QPushButton::clicked, this, &SimulationWidget::GetAvailableWorlds);
connect(ui_->loadWorldButton, &QPushButton::clicked, this, &SimulationWidget::LoadWorld);
connect(ui_->unloadWorldButton, &QPushButton::clicked, this, &SimulationWidget::UnloadWorld);

// Connect spawn position spin boxes to update marker
connect(ui_->doubleSpinBoxX, QOverload<double>::of(&QDoubleSpinBox::valueChanged), this,
Expand Down Expand Up @@ -234,6 +237,104 @@ namespace q_simulation_interfaces
setSimulationStateService_->call_service_async(cb, request);
}


void SimulationWidget::LoadWorld()
{
if (!loadWorldService_)
{
QMessageBox::warning(this, "Service Not Available",
"Load World service is not available. Please select a valid service.");
return;
}

simulation_interfaces::srv::LoadWorld::Request request;
auto selectedWorld = ui_->availableWorldsCombo->currentText();
request.uri = selectedWorld.toStdString();

std::cout << "Loading world: " << request.uri << std::endl;

auto cb = [this](auto response)
{
ProduceWarningIfProblem(this, "Load World", response);
if (response)
{
ui_->currentWorldLabel->setText("Current world: " +
QString::fromStdString(response->world.world_resource.uri));
}
};
loadWorldService_->call_service_async(cb, request);
}

void SimulationWidget::UnloadWorld()
{
if (!unloadWorldService_)
{
QMessageBox::warning(this, "Service Not Available",
"Unload World service is not available. Please select a valid service.");
return;
}

simulation_interfaces::srv::UnloadWorld::Request request;

auto cb = [this](auto response)
{
ProduceWarningIfProblem(this, "Unload World", response);
if (response)
{
ui_->currentWorldLabel->setText("Current world: ");
}
};
unloadWorldService_->call_service_async(cb, request);
}

void SimulationWidget::GetAvailableWorlds()
{
if (!getAvailableWorldsService_)
{
QMessageBox::warning(this, "Service Not Available",
"Get Available Worlds service is not available. Please select a valid service.");
return;
}

simulation_interfaces::srv::GetAvailableWorlds::Request request;
request.offline_only = true;

auto cb = [this](auto response)
{
ProduceWarningIfProblem(this, "Get Available Worlds", response);
if (response && response->result.result == simulation_interfaces::msg::Result::RESULT_OK)
{
ui_->availableWorldsCombo->clear();

auto worlds = response->worlds;
for (const auto& world : worlds)
{
ui_->availableWorldsCombo->addItem(QString::fromStdString(world.world_resource.uri));
}
}
};
getAvailableWorldsService_->call_service_async(cb, request);
}

void SimulationWidget::GetCurrentWorld()
{
if (!getCurrentWorldService_)
{
return;
}
Comment on lines 330 to 335
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

All other service handlers produce a warning if the service is not present.

simulation_interfaces::srv::GetCurrentWorld::Request request;
auto cb = [this](auto response)
{
ProduceWarningIfProblem(this, "Get Current World", response);
if (response && response->result.result == simulation_interfaces::msg::Result::RESULT_OK)
{
ui_->currentWorldLabel->setText("Current world: " +
QString::fromStdString(response->world.world_resource.uri));
}
};
getCurrentWorldService_->call_service_async(cb, request);
}

void SimulationWidget::ActionThreadWorker(int steps)
{
actionThreadRunning_.store(true);
Expand Down Expand Up @@ -877,6 +978,47 @@ namespace q_simulation_interfaces
serviceInterfaces_.insert(setSimulationStateService_);
}
break;
case ServiceType::SERVICE_GET_CURRENT_WORLD:
serviceInterfaces_.erase(getCurrentWorldService_);
getCurrentWorldService_ = shouldReset
? nullptr
: std::make_shared<Service<simulation_interfaces::srv::GetCurrentWorld>>(selectedServiceName, node_);
if (getCurrentWorldService_)
{
serviceInterfaces_.insert(getCurrentWorldService_);
}
GetCurrentWorld();
break;
case ServiceType::SERVICE_GET_AVAILABLE_WORLDS:
serviceInterfaces_.erase(getAvailableWorldsService_);
getAvailableWorldsService_ = shouldReset
? nullptr
: std::make_shared<Service<simulation_interfaces::srv::GetAvailableWorlds>>(selectedServiceName, node_);
if (getAvailableWorldsService_)
{
serviceInterfaces_.insert(getAvailableWorldsService_);
}
break;
case ServiceType::SERVICE_LOAD_WORLD:
serviceInterfaces_.erase(loadWorldService_);
loadWorldService_ = shouldReset
? nullptr
: std::make_shared<Service<simulation_interfaces::srv::LoadWorld>>(selectedServiceName, node_);
if (loadWorldService_)
{
serviceInterfaces_.insert(loadWorldService_);
}
break;
case ServiceType::SERVICE_UNLOAD_WORLD:
serviceInterfaces_.erase(unloadWorldService_);
unloadWorldService_ = shouldReset
? nullptr
: std::make_shared<Service<simulation_interfaces::srv::UnloadWorld>>(selectedServiceName, node_);
if (unloadWorldService_)
{
serviceInterfaces_.insert(unloadWorldService_);
}
break;
case ServiceType::ACTION_SIMULATE_STEPS:
simulateStepsAction_ = selectedServiceName;
break;
Expand Down
13 changes: 12 additions & 1 deletion src/simulation_widget.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,15 +30,19 @@
#include <QComboBox>
#include <q_simulation_interfaces/service_discovery.h>
#include <simulation_interfaces/srv/delete_entity.hpp>
#include <simulation_interfaces/srv/get_available_worlds.hpp>
#include <simulation_interfaces/srv/get_current_world.hpp>
#include <simulation_interfaces/srv/get_entities.hpp>
#include <simulation_interfaces/srv/get_entity_state.hpp>
#include <simulation_interfaces/srv/get_simulation_state.hpp>
#include <simulation_interfaces/srv/get_spawnables.hpp>
#include <simulation_interfaces/srv/load_world.hpp>
#include <simulation_interfaces/srv/reset_simulation.hpp>
#include <simulation_interfaces/srv/set_entity_state.hpp>
#include <simulation_interfaces/srv/set_simulation_state.hpp>
#include <simulation_interfaces/srv/spawn_entity.hpp>
#include <simulation_interfaces/srv/step_simulation.hpp>
#include <simulation_interfaces/srv/unload_world.hpp>

namespace Ui
{
Expand All @@ -65,7 +69,6 @@ namespace q_simulation_interfaces
void hideEvent(QHideEvent* event) override;
void showEvent(QShowEvent* event) override;

void onShowServicesTab();
void GetSpawnables();
void SpawnButton();
void GetAllEntities();
Expand All @@ -78,6 +81,10 @@ namespace q_simulation_interfaces
void GetSimulationState();
void SetSimulationState();
void StepSimulationService();
void LoadWorld();
void UnloadWorld();
void GetAvailableWorlds();
void GetCurrentWorld();

//! The thread with own ROS 2 node that will run the action client
void ActionThreadWorker(int steps);
Expand Down Expand Up @@ -112,6 +119,10 @@ namespace q_simulation_interfaces
std::shared_ptr<Service<simulation_interfaces::srv::GetSimulationState>> getSimulationStateService_;
std::shared_ptr<Service<simulation_interfaces::srv::SetSimulationState>> setSimulationStateService_;
std::shared_ptr<Service<simulation_interfaces::srv::StepSimulation>> stepSimulationService_;
std::shared_ptr<Service<simulation_interfaces::srv::GetAvailableWorlds>> getAvailableWorldsService_;
std::shared_ptr<Service<simulation_interfaces::srv::GetCurrentWorld>> getCurrentWorldService_;
std::shared_ptr<Service<simulation_interfaces::srv::LoadWorld>> loadWorldService_;
std::shared_ptr<Service<simulation_interfaces::srv::UnloadWorld>> unloadWorldService_;

// Action names
std::string simulateStepsAction_ = "";
Expand Down
14 changes: 14 additions & 0 deletions src/string_to_keys.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,14 @@ const std::map<int, std::string> FeatureToName{
{31, "STEP_SIMULATION_SINGLE"},
{32, "STEP_SIMULATION_MULTIPLE"},
{33, "STEP_SIMULATION_ACTION"},
{40, "WORLD_LOADING"},
{41, "WORLD_RESOURCE_STRING"},
{42, "WORLD_TAGS"},
{43, "WORLD_UNLOADING"},
{44, "WORLD_INFO_GETTING"},
{45, "AVAILABLE_WORLDS"},
};

const std::map<int, std::string> FeatureDescription{
{0, "Supports spawn interface (SpawnEntity)."},
{1, "Supports deleting entities (DeleteEntity)."},
Expand All @@ -71,7 +78,14 @@ const std::map<int, std::string> FeatureDescription{
{31, "Supports single stepping through simulation with StepSimulation interface."},
{32, "Supports multi-stepping through simulation, either through StepSimulation service or StepSimulation action."},
{33, "Supports SimulateSteps action interface."},
{40, "Supports loading worlds through LoadWorld interface."},
{41, "Supports resource_string field in LoadWorld interface."},
{42, "Supports tags field in LoadWorld interface."},
{43, "Supports unloading worlds through UnloadWorld interface."},
{44, "Supports GetWorldInfo interface."},
{45, "Supports GetAvailableWorlds interface."},
};

const std::unordered_map<std::string, int> ScopeNameToId{
{"SCOPE_DEFAULT", 0}, {"SCOPE_TIME", 1}, {"SCOPE_STATE", 2}, {"SCOPE_SPAWNED", 4}, {"SCOPE_ALL", 255},
};
Expand Down