Commit ed0f21c9 authored by DonLakeFlyer's avatar DonLakeFlyer

parent 729aafbe
...@@ -24,9 +24,10 @@ public: ...@@ -24,9 +24,10 @@ public:
const ComplexMissionItem& operator=(const ComplexMissionItem& other); const ComplexMissionItem& operator=(const ComplexMissionItem& other);
Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged) Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged)
Q_PROPERTY(bool presetsSupported READ presetsSupported CONSTANT) Q_PROPERTY(bool presetsSupported READ presetsSupported CONSTANT)
Q_PROPERTY(QStringList presetNames READ presetNames NOTIFY presetNamesChanged) Q_PROPERTY(QStringList presetNames READ presetNames NOTIFY presetNamesChanged)
Q_PROPERTY(bool isIncomplete READ isIncomplete NOTIFY isIncompleteChanged)
/// @return The distance covered the complex mission item in meters. /// @return The distance covered the complex mission item in meters.
/// Signals complexDistanceChanged /// Signals complexDistanceChanged
...@@ -64,7 +65,8 @@ public: ...@@ -64,7 +65,8 @@ public:
/// Empty string signals no support for presets. /// Empty string signals no support for presets.
virtual QString presetsSettingsGroup(void) { return QString(); } virtual QString presetsSettingsGroup(void) { return QString(); }
bool presetsSupported(void) { return !presetsSettingsGroup().isEmpty(); } bool presetsSupported (void) { return !presetsSettingsGroup().isEmpty(); }
bool isIncomplete (void) const { return _isIncomplete; }
/// This mission item attribute specifies the type of the complex item. /// This mission item attribute specifies the type of the complex item.
static const char* jsonComplexItemTypeKey; static const char* jsonComplexItemTypeKey;
...@@ -74,11 +76,13 @@ signals: ...@@ -74,11 +76,13 @@ signals:
void boundingCubeChanged (void); void boundingCubeChanged (void);
void greatestDistanceToChanged (void); void greatestDistanceToChanged (void);
void presetNamesChanged (void); void presetNamesChanged (void);
void isIncompleteChanged (void);
protected: protected:
void _savePresetJson (const QString& name, QJsonObject& presetObject); void _savePresetJson (const QString& name, QJsonObject& presetObject);
QJsonObject _loadPresetJson (const QString& name); QJsonObject _loadPresetJson (const QString& name);
bool _isIncomplete = true;
QMap<QString, FactMetaData*> _metaDataMap; QMap<QString, FactMetaData*> _metaDataMap;
......
...@@ -66,6 +66,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool ...@@ -66,6 +66,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool
, _altitudesAreRelative (true) , _altitudesAreRelative (true)
{ {
_editorQml = "qrc:/qml/FWLandingPatternEditor.qml"; _editorQml = "qrc:/qml/FWLandingPatternEditor.qml";
_isIncomplete = false;
connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact); connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact);
connect(&_landingAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLandingCoodinateAltitudeFromFact); connect(&_landingAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLandingCoodinateAltitudeFromFact);
......
...@@ -1139,6 +1139,26 @@ double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, Vi ...@@ -1139,6 +1139,26 @@ double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, Vi
return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0; return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
} }
CoordinateVector* MissionController::_createCoordinateVectorWorker(VisualItemPair& pair)
{
CoordinateVector* coordVector = nullptr;
// Create a new segment and wire update notifiers
coordVector = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
auto endNotifier = &VisualMissionItem::coordinateChanged;
// Use signals/slots to update the coordinate endpoints
connect(pair.first, originNotifier, coordVector, &CoordinateVector::setCoordinate1);
connect(pair.second, endNotifier, coordVector, &CoordinateVector::setCoordinate2);
// FIXME: We should ideally have signals for 2D position change, alt change, and 3D position change
// Not optimal, but still pretty fast, do a full update of range/bearing/altitudes
connect(pair.second, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
return coordVector;
}
CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair) CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
{ {
CoordinateVector* coordVector = nullptr; CoordinateVector* coordVector = nullptr;
...@@ -1147,18 +1167,7 @@ CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable& ...@@ -1147,18 +1167,7 @@ CoordinateVector* MissionController::_addWaypointLineSegment(CoordVectHashTable&
// Pair already exists and connected, just re-use // Pair already exists and connected, just re-use
_linesTable[pair] = coordVector = prevItemPairHashTable.take(pair); _linesTable[pair] = coordVector = prevItemPairHashTable.take(pair);
} else { } else {
// Create a new segment and wire update notifiers coordVector = _createCoordinateVectorWorker(pair);
coordVector = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
auto endNotifier = &VisualMissionItem::coordinateChanged;
// Use signals/slots to update the coordinate endpoints
connect(pair.first, originNotifier, coordVector, &CoordinateVector::setCoordinate1);
connect(pair.second, endNotifier, coordVector, &CoordinateVector::setCoordinate2);
// FIXME: We should ideally have signals for 2D position change, alt change, and 3D position change
// Not optimal, but still pretty fast, do a full update of range/bearing/altitudes
connect(pair.second, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
_linesTable[pair] = coordVector; _linesTable[pair] = coordVector;
} }
...@@ -1209,6 +1218,8 @@ void MissionController::_recalcWaypointLines(void) ...@@ -1209,6 +1218,8 @@ void MissionController::_recalcWaypointLines(void)
bool foundRTL = false; bool foundRTL = false;
bool homePositionValid = _settingsItem->coordinate().isValid(); bool homePositionValid = _settingsItem->coordinate().isValid();
bool roiActive = false; bool roiActive = false;
bool setupIncompleteItem = false;
VisualMissionItem* startVIForIncompleteItem = nullptr;
qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid; qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
...@@ -1219,15 +1230,18 @@ void MissionController::_recalcWaypointLines(void) ...@@ -1219,15 +1230,18 @@ void MissionController::_recalcWaypointLines(void)
_waypointLines.beginReset(); _waypointLines.beginReset();
_directionArrows.beginReset(); _directionArrows.beginReset();
_incompleteComplexItemLines.beginReset();
_waypointLines.clear(); _waypointLines.clear();
_directionArrows.clear(); _directionArrows.clear();
_incompleteComplexItemLines.clearAndDeleteContents();
// Grovel through the list of items keeping track of things needed to correctly draw waypoints lines // Grovel through the list of items keeping track of things needed to correctly draw waypoints lines
for (int i=1; i<_visualItems->count(); i++) { for (int i=1; i<_visualItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i)); VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem); SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
if (simpleItem) { if (simpleItem) {
if (roiActive) { if (roiActive) {
...@@ -1267,29 +1281,47 @@ void MissionController::_recalcWaypointLines(void) ...@@ -1267,29 +1281,47 @@ void MissionController::_recalcWaypointLines(void)
} }
if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) { if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
if (lastCoordinateItemBeforeRTL != _settingsItem || (homePositionValid && linkStartToHome)) { // Incomplete items are complex items which are waiting for the user to complete setup before there visuals can become valid.
// Direction arrows are added to the first segment and every 5 segments in the middle. // For example a Survey which has no polygon set for it yet. For these cases we draw incomplete segment lines so that there
bool addDirectionArrow = false; // isn't a hole in the flight path lines.
if (firstCoordinateNotFound || !lastCoordinateItemBeforeRTL->isSimpleItem() || !visualItem->isSimpleItem()) { if (complexItem && complexItem->isIncomplete()) {
addDirectionArrow = true; setupIncompleteItem = true;
} else if (segmentCount > 5) { } else {
segmentCount = 0; if (setupIncompleteItem) {
addDirectionArrow = true; VisualItemPair viPair(startVIForIncompleteItem, visualItem);
CoordinateVector* coordVector = _createCoordinateVectorWorker(viPair);
_incompleteComplexItemLines.append(coordVector);
startVIForIncompleteItem = nullptr;
setupIncompleteItem = false;
} else {
startVIForIncompleteItem = visualItem;
} }
segmentCount++;
if (lastCoordinateItemBeforeRTL != _settingsItem || (homePositionValid && linkStartToHome)) {
lastSegmentVisualItemPair = VisualItemPair(lastCoordinateItemBeforeRTL, visualItem); // Direction arrows are added to the first segment and every 5 segments in the middle.
if (!_flyView || addDirectionArrow) { bool addDirectionArrow = false;
CoordinateVector* coordVector = _addWaypointLineSegment(old_table, lastSegmentVisualItemPair); if (firstCoordinateNotFound || !lastCoordinateItemBeforeRTL->isSimpleItem() || !visualItem->isSimpleItem()) {
coordVector->setSpecialVisual(roiActive); addDirectionArrow = true;
if (addDirectionArrow) { } else if (segmentCount > 5) {
_directionArrows.append(coordVector); segmentCount = 0;
addDirectionArrow = true;
}
segmentCount++;
lastSegmentVisualItemPair = VisualItemPair(lastCoordinateItemBeforeRTL, visualItem);
if (!_flyView || addDirectionArrow) {
CoordinateVector* coordVector = _addWaypointLineSegment(old_table, lastSegmentVisualItemPair);
coordVector->setSpecialVisual(roiActive);
if (addDirectionArrow) {
_directionArrows.append(coordVector);
}
} }
} }
firstCoordinateNotFound = false;
_waypointPath.append(QVariant::fromValue(visualItem->coordinate()));
lastCoordinateItemBeforeRTL = visualItem;
} }
firstCoordinateNotFound = false;
_waypointPath.append(QVariant::fromValue(visualItem->coordinate()));
lastCoordinateItemBeforeRTL = visualItem;
} }
} }
...@@ -1342,6 +1374,7 @@ void MissionController::_recalcWaypointLines(void) ...@@ -1342,6 +1374,7 @@ void MissionController::_recalcWaypointLines(void)
_waypointLines.endReset(); _waypointLines.endReset();
_directionArrows.endReset(); _directionArrows.endReset();
_incompleteComplexItemLines.endReset();
// Anything left in the old table is an obsolete line object that can go // Anything left in the old table is an obsolete line object that can go
qDeleteAll(old_table); qDeleteAll(old_table);
...@@ -1852,6 +1885,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) ...@@ -1852,6 +1885,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
if (complexItem) { if (complexItem) {
connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus); connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged, this, &MissionController::_recalcMissionFlightStatus); connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::isIncompleteChanged, this, &MissionController::_recalcWaypointLines);
} else { } else {
qWarning() << "ComplexMissionItem not found"; qWarning() << "ComplexMissionItem not found";
} }
......
...@@ -70,6 +70,7 @@ public: ...@@ -70,6 +70,7 @@ public:
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines CONSTANT) ///< Used by Plan view only for interactive editing Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines CONSTANT) ///< Used by Plan view only for interactive editing
Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged) ///< Used by Fly view only for static display Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged) ///< Used by Fly view only for static display
Q_PROPERTY(QmlObjectListModel* directionArrows READ directionArrows CONSTANT) Q_PROPERTY(QmlObjectListModel* directionArrows READ directionArrows CONSTANT)
Q_PROPERTY(QmlObjectListModel* incompleteComplexItemLines READ incompleteComplexItemLines CONSTANT) ///< Segments which are not yet completed.
Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged) Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged)
Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
Q_PROPERTY(QGeoCoordinate previousCoordinate MEMBER _previousCoordinate NOTIFY previousCoordinateChanged) Q_PROPERTY(QGeoCoordinate previousCoordinate MEMBER _previousCoordinate NOTIFY previousCoordinateChanged)
...@@ -200,6 +201,7 @@ public: ...@@ -200,6 +201,7 @@ public:
QmlObjectListModel* visualItems (void) { return _visualItems; } QmlObjectListModel* visualItems (void) { return _visualItems; }
QmlObjectListModel* waypointLines (void) { return &_waypointLines; } QmlObjectListModel* waypointLines (void) { return &_waypointLines; }
QmlObjectListModel* directionArrows (void) { return &_directionArrows; } QmlObjectListModel* directionArrows (void) { return &_directionArrows; }
QmlObjectListModel* incompleteComplexItemLines (void) { return &_incompleteComplexItemLines; }
QVariantList waypointPath (void) { return _waypointPath; } QVariantList waypointPath (void) { return _waypointPath; }
QStringList complexMissionItemNames (void) const; QStringList complexMissionItemNames (void) const;
QGeoCoordinate plannedHomePosition (void) const; QGeoCoordinate plannedHomePosition (void) const;
...@@ -270,20 +272,20 @@ signals: ...@@ -270,20 +272,20 @@ signals:
void previousCoordinateChanged (void); void previousCoordinateChanged (void);
private slots: private slots:
void _newMissionItemsAvailableFromVehicle(bool removeAllRequested); void _newMissionItemsAvailableFromVehicle (bool removeAllRequested);
void _itemCommandChanged(void); void _itemCommandChanged (void);
void _inProgressChanged(bool inProgress); void _inProgressChanged (bool inProgress);
void _currentMissionIndexChanged(int sequenceNumber); void _currentMissionIndexChanged (int sequenceNumber);
void _recalcWaypointLines(void); void _recalcWaypointLines (void);
void _recalcMissionFlightStatus(void); void _recalcMissionFlightStatus (void);
void _updateContainsItems(void); void _updateContainsItems (void);
void _progressPctChanged(double progressPct); void _progressPctChanged (double progressPct);
void _visualItemsDirtyChanged(bool dirty); void _visualItemsDirtyChanged (bool dirty);
void _managerSendComplete(bool error); void _managerSendComplete (bool error);
void _managerRemoveAllComplete(bool error); void _managerRemoveAllComplete (bool error);
void _updateTimeout(); void _updateTimeout (void);
void _complexBoundingBoxChanged(); void _complexBoundingBoxChanged (void);
void _recalcAll(void); void _recalcAll (void);
private: private:
void _init(void); void _init(void);
...@@ -324,6 +326,7 @@ private: ...@@ -324,6 +326,7 @@ private:
void _warnIfTerrainFrameUsed(void); void _warnIfTerrainFrameUsed(void);
bool _isROIBeginItem(SimpleMissionItem* simpleItem); bool _isROIBeginItem(SimpleMissionItem* simpleItem);
bool _isROICancelItem(SimpleMissionItem* simpleItem); bool _isROICancelItem(SimpleMissionItem* simpleItem);
CoordinateVector* _createCoordinateVectorWorker(VisualItemPair& pair);
private: private:
MissionManager* _missionManager; MissionManager* _missionManager;
...@@ -333,6 +336,7 @@ private: ...@@ -333,6 +336,7 @@ private:
QmlObjectListModel _waypointLines; QmlObjectListModel _waypointLines;
QVariantList _waypointPath; QVariantList _waypointPath;
QmlObjectListModel _directionArrows; QmlObjectListModel _directionArrows;
QmlObjectListModel _incompleteComplexItemLines;
CoordVectHashTable _linesTable; CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle; bool _firstItemsFromVehicle;
bool _itemsRequested; bool _itemsRequested;
......
...@@ -264,6 +264,11 @@ void StructureScanComplexItem::_flightPathChanged(void) ...@@ -264,6 +264,11 @@ void StructureScanComplexItem::_flightPathChanged(void)
emit coordinateChanged(coordinate()); emit coordinateChanged(coordinate());
emit exitCoordinateChanged(exitCoordinate()); emit exitCoordinateChanged(exitCoordinate());
emit greatestDistanceToChanged(); emit greatestDistanceToChanged();
if (_isIncomplete) {
_isIncomplete = false;
emit isIncompleteChanged();
}
} }
double StructureScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const double StructureScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
...@@ -282,11 +287,6 @@ double StructureScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other) ...@@ -282,11 +287,6 @@ double StructureScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other)
return greatestDistance; return greatestDistance;
} }
bool StructureScanComplexItem::specifiesCoordinate(void) const
{
return _flightPolygon.count() > 2;
}
void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{ {
int seqNum = _sequenceNumber; int seqNum = _sequenceNumber;
......
...@@ -73,7 +73,7 @@ public: ...@@ -73,7 +73,7 @@ public:
bool dirty (void) const final { return _dirty; } bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return false; } bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; } bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesCoordinate (void) const final; bool specifiesCoordinate (void) const final { return true; }
bool specifiesAltitudeOnly (void) const final { return false; } bool specifiesAltitudeOnly (void) const final { return false; }
QString commandDescription (void) const final { return tr("Structure Scan"); } QString commandDescription (void) const final { return tr("Structure Scan"); }
QString commandName (void) const final { return tr("Structure Scan"); } QString commandName (void) const final { return tr("Structure Scan"); }
...@@ -129,7 +129,6 @@ private slots: ...@@ -129,7 +129,6 @@ private slots:
void _recalcScanDistance (void); void _recalcScanDistance (void);
private: private:
void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _setCameraShots(int cameraShots); void _setCameraShots(int cameraShots);
double _triggerDistance(void) const; double _triggerDistance(void) const;
......
...@@ -230,6 +230,7 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forP ...@@ -230,6 +230,7 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forP
} }
_coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate(); _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate(); _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
_isIncomplete = false;
// Load generated mission items // Load generated mission items
_loadedMissionItemsParent = new QObject(this); _loadedMissionItemsParent = new QObject(this);
...@@ -408,6 +409,11 @@ void TransectStyleComplexItem::_rebuildTransects(void) ...@@ -408,6 +409,11 @@ void TransectStyleComplexItem::_rebuildTransects(void)
emit coordinateChanged(_coordinate); emit coordinateChanged(_coordinate);
emit exitCoordinateChanged(_exitCoordinate); emit exitCoordinateChanged(_exitCoordinate);
if (_isIncomplete) {
_isIncomplete = false;
emit isIncompleteChanged();
}
_recalcComplexDistance(); _recalcComplexDistance();
_recalcCameraShots(); _recalcCameraShots();
......
...@@ -434,6 +434,7 @@ Item { ...@@ -434,6 +434,7 @@ Item {
model: _editingLayer == _layerMission ? _missionController.waypointLines : undefined model: _editingLayer == _layerMission ? _missionController.waypointLines : undefined
} }
// Direction arrows in waypoint lines
MapItemView { MapItemView {
model: _editingLayer == _layerMission ? _missionController.directionArrows : undefined model: _editingLayer == _layerMission ? _missionController.directionArrows : undefined
...@@ -445,6 +446,18 @@ Item { ...@@ -445,6 +446,18 @@ Item {
} }
} }
// Incomplete segment lines
MapItemView {
model: _editingLayer == _layerMission ? _missionController.incompleteComplexItemLines : undefined
delegate: MapPolyline {
path: [ object.coordinate1, object.coordinate2 ]
line.width: 1
line.color: "red"
z: QGroundControl.zOrderWaypointLines
}
}
// UI for splitting the current segment // UI for splitting the current segment
MapQuickItem { MapQuickItem {
id: splitSegmentItem id: splitSegmentItem
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment