Skip to content

Commit

Permalink
Merge branch 'release/v1.0.4' into main
Browse files Browse the repository at this point in the history
  • Loading branch information
mgrova committed Jul 5, 2023
2 parents 1fe3824 + 0c940e0 commit 0111454
Show file tree
Hide file tree
Showing 15 changed files with 59 additions and 45 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ cd .. && catkin_make -DCMAKE_BUILD_TYPE=Release
* Via the default way of cmake creating a build folder:
```
git clone https://github.com/fada-catec/piloting_grcs && cd piloting_gcs
git clone https://github.com/fada-catec/piloting_grcs && cd piloting_grcs
mkdir build && cd build && cmake .. -DCMAKE_BUILD_TYPE=Release
Expand Down
16 changes: 16 additions & 0 deletions changelog.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,19 @@
----------------------------------------------
-- Changelog for version 1.0.4 (2023-07-05) --
----------------------------------------------
The changes of this version are small improvements after the release of the code and a the fix of a bug in the representation of the Inspection Areas.

* In DDHL, new fields have been added in the Inspection Location properties to define the Inspection Plan orientation in the global
reference frame: quatW, quatX, quatY and quatZ. These fields are read instead of the "repr" matrix to represent the Inspection Area.

* When using "Ctrl + Arrows Keys" to edit a waypoint manually in route editing mode the last one was moved. Now the one that is selected
in the gRCS is edited.

* Added server response to the logging message when POST call fails during post-mission data upload.

----------------------------------------------------------------------------------------------------------------------------------------------
----------------------------------------------------------------------------------------------------------------------------------------------

----------------------------------------------
-- Changelog for version 1.0.3 (2023-05-21) --
----------------------------------------------
Expand Down
2 changes: 1 addition & 1 deletion cmake_stuff/versions.cmake
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
SET(VERSION "1.0.3")
SET(VERSION "1.0.4")
STRING(REGEX MATCHALL "[0-9]" VERSION_PARTS "${VERSION}")
LIST(GET VERSION_PARTS 0 VERSION_MAJOR)
LIST(GET VERSION_PARTS 1 VERSION_MINOR)
Expand Down
Binary file removed data/icons/cloud-icon.png
Binary file not shown.
Binary file removed data/icons/config-visualiz-icon-2.png
Binary file not shown.
Binary file modified data/icons/config-visualiz-icon.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<package format="2">

<name>piloting_grcs</name>
<version>1.0.3</version>
<version>1.0.4</version>
<description>The piloting_grcs package</description>

<maintainer email="mmontes@catec.aero">Marco A. Montes Grova</maintainer>
Expand Down
26 changes: 6 additions & 20 deletions src/communications/DDHL/JSon2DTO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,34 +176,20 @@ QList<InspectionTaskDTO> JSon2DTO::convertInspectionTaskJsonArrayToList(const QJ
inspTaskDTO.getLocationType() = InspectionTaskLocationType::POINT;
} else if (QString::compare(readedType, "InspectionArea", Qt::CaseInsensitive) == 0) {
inspTaskDTO.getLocationType() = InspectionTaskLocationType::AREA;
_jsonKeys.checkIfValidInspTaskAreaDimensions(inspTaskDimensionsJO);
_jsonKeys.checkIfValidInspTaskAreaParams(inspTaskDimensionsJO);
inspTaskDTO.getWidth() = inspTaskDimensionsJO["width"].toDouble();
inspTaskDTO.getDepth() = inspTaskDimensionsJO["depth"].toDouble();
inspTaskDTO.getHeight() = inspTaskDimensionsJO["height"].toDouble();

const QJsonObject reprJO = inspTaskDimensionsJO["repr"].toObject();
_jsonKeys.checkKeyExist(reprJO, "matrix");

const QJsonArray matrixJA = reprJO["matrix"].toArray();
if (matrixJA.size() != 16) {
throw std::runtime_error("Invalid repr matrix size");
}

/// \note. Column-major order arrived matrix
Eigen::Matrix3f m(3, 3);
m << matrixJA[0].toDouble(), matrixJA[4].toDouble(), matrixJA[8].toDouble(), matrixJA[1].toDouble(),
matrixJA[5].toDouble(), matrixJA[9].toDouble(), matrixJA[2].toDouble(), matrixJA[6].toDouble(),
matrixJA[10].toDouble();
Eigen::Quaternionf q(m);
inspTaskDTO.getOrientation().getX() = q.x();
inspTaskDTO.getOrientation().getY() = q.y();
inspTaskDTO.getOrientation().getZ() = q.z();
inspTaskDTO.getOrientation().getW() = q.w();
inspTaskDTO.getOrientation().getW() = inspTaskDimensionsJO["quatW"].toDouble();
inspTaskDTO.getOrientation().getX() = inspTaskDimensionsJO["quatX"].toDouble();
inspTaskDTO.getOrientation().getY() = inspTaskDimensionsJO["quatY"].toDouble();
inspTaskDTO.getOrientation().getZ() = inspTaskDimensionsJO["quatZ"].toDouble();
} else {
throw std::runtime_error("Invalid inspection task type readed from DDHL");
}

_jsonKeys.checkIfValidInspTaskPointDimensions(inspTaskDimensionsJO);
_jsonKeys.checkIfValidInspTaskPointParams(inspTaskDimensionsJO);
inspTaskDTO.getPosition().getX() = inspTaskDimensionsJO["posX"].toDouble();
inspTaskDTO.getPosition().getY() = inspTaskDimensionsJO["posY"].toDouble();
inspTaskDTO.getPosition().getZ() = inspTaskDimensionsJO["posZ"].toDouble();
Expand Down
21 changes: 12 additions & 9 deletions src/communications/DDHL/JSonKeys.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,19 +61,22 @@ void JSonKeys::checkIfValidInspTaskLocation(const QJsonObject& inspTaskLocation)
checkKeyExist(inspTaskLocation, "Properties");
}

void JSonKeys::checkIfValidInspTaskAreaDimensions(const QJsonObject& inspTaskAreaDimensions)
void JSonKeys::checkIfValidInspTaskAreaParams(const QJsonObject& inspTaskAreaParams)
{
checkKeyExist(inspTaskAreaDimensions, "width");
checkKeyExist(inspTaskAreaDimensions, "depth");
checkKeyExist(inspTaskAreaDimensions, "height");
checkKeyExist(inspTaskAreaDimensions, "repr");
checkKeyExist(inspTaskAreaParams, "width");
checkKeyExist(inspTaskAreaParams, "depth");
checkKeyExist(inspTaskAreaParams, "height");
checkKeyExist(inspTaskAreaParams, "quatW");
checkKeyExist(inspTaskAreaParams, "quatX");
checkKeyExist(inspTaskAreaParams, "quatY");
checkKeyExist(inspTaskAreaParams, "quatZ");
}

void JSonKeys::checkIfValidInspTaskPointDimensions(const QJsonObject& inspTaskPointDimensions)
void JSonKeys::checkIfValidInspTaskPointParams(const QJsonObject& inspTaskPointParams)
{
checkKeyExist(inspTaskPointDimensions, "posX");
checkKeyExist(inspTaskPointDimensions, "posY");
checkKeyExist(inspTaskPointDimensions, "posZ");
checkKeyExist(inspTaskPointParams, "posX");
checkKeyExist(inspTaskPointParams, "posY");
checkKeyExist(inspTaskPointParams, "posZ");
}

void JSonKeys::checkIfValidInspTaskType(const QJsonObject& inspTaskType)
Expand Down
4 changes: 2 additions & 2 deletions src/communications/DDHL/JSonKeys.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ class JSonKeys : public QObject
void checkIfValidInspPlan(const QJsonObject&);
void checkIfValidInspTask(const QJsonObject&);
void checkIfValidInspTaskLocation(const QJsonObject&);
void checkIfValidInspTaskAreaDimensions(const QJsonObject&);
void checkIfValidInspTaskPointDimensions(const QJsonObject&);
void checkIfValidInspTaskAreaParams(const QJsonObject&);
void checkIfValidInspTaskPointParams(const QJsonObject&);
void checkIfValidInspTaskType(const QJsonObject&);
void checkIfValidAsset(const QJsonObject&);
void checkIfValidSite(const QJsonObject&);
Expand Down
3 changes: 2 additions & 1 deletion src/communications/DDHL/RestApiClient.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,8 @@ void RestApiClient::handlePostResult(HttpRequestWorker* worker)
QLOG_INFO() << __PRETTY_FUNCTION__ << "Post request response: " << worker->response;

if (worker->error_type != QNetworkReply::NoError) {
throw std::runtime_error(worker->error_str.toStdString());
throw std::runtime_error(
worker->error_str.toStdString() + " | Server Response: " + worker->response.toStdString());
}

QJsonParseError* e = nullptr;
Expand Down
5 changes: 3 additions & 2 deletions src/gui/MainWindowUi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,11 +92,11 @@ MainWindowUi::MainWindowUi(QWidget* parent) :
/// \note LeftDockWidgetArea
setTelemetryTreeDock(Qt::LeftDockWidgetArea);
setInspectionPlanDock(Qt::LeftDockWidgetArea);
setMissionDock(Qt::LeftDockWidgetArea);

/// \note RightDockWidgetArea
setRobotAlarmsDock(Qt::RightDockWidgetArea);
setRobotControlDock(Qt::RightDockWidgetArea);
setMissionDock(Qt::RightDockWidgetArea);
setHighLevelActionsDock(Qt::RightDockWidgetArea);

/// \note BottomDockWidgetArea
Expand Down Expand Up @@ -427,6 +427,8 @@ void MainWindowUi::manageCoreDTO(QSharedPointer<IDTO> idto)

_inspectionPlanWidget.setInspectionPlan(dto);
_waypointEditorWidget.updateInspectionTaskList(dto->getInspectionTaskList());

updateMissionButtons();
}
break;
}
Expand Down Expand Up @@ -1163,7 +1165,6 @@ void MainWindowUi::updateMissionButtons()
const auto hasRoutes = _guiDTO.getHasRoutes();
const auto isConnected = _guiDTO.getCommsIsConnected();
const auto isEditMode = _ui->editModeAct->isChecked();
// const auto hasInspPlan = !_guiDTO.getInspectionPlan().getInspectionTaskList().isEmpty();
const auto hasInspPlan = !_guiDTO.getInspectionPlan().getUUID().isEmpty();

_ui->saveCurrWptsListAct->setEnabled(hasInspPlan && hasRoutes);
Expand Down
2 changes: 1 addition & 1 deletion src/gui/widgets/robotAlarms/RobotAlarmsWidget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ void RobotAlarmsWidget::update(const AlarmStatusDTO& alarmStatusDTO)

const auto current_item = _items[alarmStatusDTO.getIndex()];
if (!current_item) {
QLOG_ERROR() << __PRETTY_FUNCTION__ << "Invalid alarm index to update";
QLOG_ERROR() << __PRETTY_FUNCTION__ << "Invalid alarm index to update: " << alarmStatusDTO.getIndex();
return;
}

Expand Down
4 changes: 2 additions & 2 deletions src/images.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,9 @@
<file alias="3d-view">../data/icons/3d-view.png</file>
<file alias="checkbox_checked">../data/icons/checkbox-icon.png</file>
<file alias="checklist">../data/icons/checklist.png</file>
<file alias="cloud-icon">../data/icons/cloud-icon.png</file>
<file alias="cloud-cut">../data/icons/cloud-cut.png</file>
<file alias="config">../data/icons/config.png</file>
<file alias="config-visualiz">../data/icons/config-visualiz-icon-2.png</file>
<file alias="config-visualiz">../data/icons/config-visualiz-icon.png</file>
<file alias="connect">../data/icons/connect.png</file>
<file alias="ddhl-config">../data/icons/ddhl-config.png</file>
<file alias="disconnect">../data/icons/disconnect.png</file>
Expand Down Expand Up @@ -52,6 +51,7 @@
<file alias="pfd_hsi_marks">../data/svg/pfd/pfd_hsi_marks.svg</file>
<file alias="pfd_mask">../data/svg/pfd/pfd_mask.svg</file>
</qresource>

<qresource prefix="/Style">
<file alias="indoorStyle">../data/styles/indoor_style.qss</file>
<file alias="outdoorStyle">../data/styles/outdoor_style.qss</file>
Expand Down
17 changes: 12 additions & 5 deletions src/maps/data_types/tools/QMouseTool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -227,17 +227,24 @@ int QMouseTool::processKeyEvent(QKeyEvent* event, rviz::RenderPanel* panel)
return Render;
}

if (_mapDTO.getVisibleWaypointsList().isEmpty()) {
/// \note. Get selected waypoint
const auto it = std::find_if(
_mapDTO.getVisibleWaypointsList().cbegin(),
_mapDTO.getVisibleWaypointsList().cend(),
[&](const QSharedPointer<Waypoint3dItem> wp) { return wp->isSelectedWaypoint(); });
if (it == _mapDTO.getVisibleWaypointsList().cend()) {
QLOG_WARN() << __PRETTY_FUNCTION__ << " - "
<< "Unable to move waypoint. No waypoint selected";
return Render;
}

float targetAngle;
const auto waypoint_id = _mapDTO.getVisibleWaypointsList().back()->id();
auto waypoint_pt = _mapDTO.getVisibleWaypointsList().back()->waypoint().getPosition();
const auto waypoint_id = (*it)->id();
const auto waypoint_pt = (*it)->waypoint().getPosition();
Ogre::Vector3 updated_waypoint(waypoint_pt.getX(), waypoint_pt.getY(), waypoint_pt.getZ());

/// \note. To be able to move waypoint using arrow keys, must be pressed Control
int visible = false;
float targetAngle;
int visible = false;
if (event->type() == QKeyEvent::KeyPress && event->modifiers() & Qt::ControlModifier) {
visible = true;
const float movementIncrement = 0.1f;
Expand Down

0 comments on commit 0111454

Please sign in to comment.