Skip to content

Commit

Permalink
Documentation and style
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Aug 13, 2021
1 parent 73b9e4e commit caf08a9
Show file tree
Hide file tree
Showing 3 changed files with 57 additions and 23 deletions.
4 changes: 4 additions & 0 deletions include/ignition/gazebo/gui/GuiEvents.hh
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ namespace events
private: bool fromUser{false};
};

/// \brief True if a transform control is currently active (translate /
/// rotate / scale). False if we're in selection mode.
class TransformControlMode : public QEvent
{
/// \brief Constructor
Expand All @@ -111,11 +113,13 @@ namespace events
/// \brief Unique type for this event.
static const QEvent::Type kType = QEvent::Type(QEvent::User + 6);

/// \brief Get the event's value.
public: bool TransformControl()
{
return this->tranformModeActive;
}

/// \brief True if a transform mode is active.
private: bool tranformModeActive;
};
} // namespace events
Expand Down
44 changes: 32 additions & 12 deletions src/gui/plugins/select_entities/SelectEntities.cc
Original file line number Diff line number Diff line change
Expand Up @@ -166,10 +166,14 @@ void SelectEntitiesPrivate::HandleEntitySelection()
this->selectedEntitiesID.push_back(this->selectedEntitiesIDNew[i]);

unsigned int entityId = kNullEntity;
try{
try
{
entityId = std::get<int>(visualToHighLight->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e){}
catch(std::bad_variant_access &_e)
{
// It's ok to get here
}

this->selectedEntities.push_back(entityId);

Expand Down Expand Up @@ -202,10 +206,14 @@ void SelectEntitiesPrivate::HandleEntitySelection()
}

unsigned int entityId = kNullEntity;
try{
try
{
entityId = std::get<int>(visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e) {}
catch(std::bad_variant_access &e)
{
// It's ok to get here
}

this->selectionHelper.selectEntity = entityId;

Expand All @@ -229,10 +237,14 @@ void SelectEntitiesPrivate::LowlightNode(const rendering::VisualPtr &_visual)
Entity entityId = kNullEntity;
if (_visual)
{
try{
try
{
entityId = std::get<int>(_visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e){}
catch(std::bad_variant_access &)
{
// It's ok to get here
}
}
if (this->wireBoxes.find(entityId) != this->wireBoxes.end())
{
Expand All @@ -253,10 +265,14 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual)
}

int entityId = kNullEntity;
try{
try
{
entityId = std::get<int>(_visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e) {}
catch(std::bad_variant_access &)
{
// It's ok to get here
}

// If the entity is not found in the existing map, create a wire box
auto wireBoxIt = this->wireBoxes.find(entityId);
Expand Down Expand Up @@ -335,10 +351,14 @@ void SelectEntitiesPrivate::SetSelectedEntity(

if (topLevelVisual)
{
try{
try
{
entityId = std::get<int>(topLevelVisual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e) {}
catch(std::bad_variant_access &)
{
// It's ok to get here
}
}

if (entityId == kNullEntity)
Expand Down Expand Up @@ -504,9 +524,9 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event)
try{
entityId = std::get<int>(visual->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &e)
catch(std::bad_variant_access &)
{
ignerr << "Error eventFilter" << std::endl;
// It's ok to get here
}

if (entityId == entity)
Expand Down
32 changes: 21 additions & 11 deletions src/gui/plugins/transform_control/TransformControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,17 @@ namespace ignition::gazebo
double _sensitivity = 0.4) const;

/// \brief Constraints the passed in axis to the currently selected axes.
/// \param[in] _axis The axis to constrain.
/// \param[in, out] _axis The axis to constrain.
public: void XYZConstraint(math::Vector3d &_axis);

/// \brief Snaps a value at intervals of a fixed distance. Currently used
/// to give a snapping behavior when moving models with a mouse.
/// \param[in] _coord Input coordinate point.
/// \param[in] _interval Fixed distance interval at which the point is
/// snapped.
/// \param[in] _sensitivity Sensitivity of a point snapping, in terms of a
/// percentage of the interval.
/// \return Snapped coordinate point.
public: double SnapValue(
double _coord, double _interval, double _sensitivity) const;

Expand All @@ -88,7 +96,7 @@ namespace ignition::gazebo
public: std::mutex mutex;

/// \brief Transform control service name
/// \brief Only used when in legacy mode, where this plugin requested a
/// Only used when in legacy mode, where this plugin requests a
/// transport service provided by `GzScene3D`.
/// The new behaviour is that this plugin performs the entire transform
/// operation.
Expand Down Expand Up @@ -138,8 +146,12 @@ namespace ignition::gazebo
/// \brief Currently selected entities, organized by order of selection.
public: std::vector<Entity> selectedEntities;

/// \brief Holds the latest mouse event
public: ignition::common::MouseEvent mouseEvent;

/// \brief Holds the latest key event
public: ignition::common::KeyEvent keyEvent;

/// \brief Flag to indicate whether the x key is currently being pressed
public: bool xPressed = false;

Expand All @@ -161,8 +173,6 @@ namespace ignition::gazebo
/// \brief The starting world pose of a clicked visual.
public: ignition::math::Vector3d startWorldPos = math::Vector3d::Zero;

public: ignition::common::KeyEvent keyEvent;

/// \brief Block orbit
public: bool blockOrbit = false;

Expand Down Expand Up @@ -243,18 +253,18 @@ void TransformControl::OnSnapUpdate(
/////////////////////////////////////////////////
void TransformControl::OnMode(const QString &_mode)
{
std::function<void(const ignition::msgs::Boolean &, const bool)> cb =
[](const ignition::msgs::Boolean &/*_rep*/, const bool _result)
{
if (!_result)
ignerr << "Error setting transform mode" << std::endl;
};

auto modeStr = _mode.toStdString();

// Legacy behaviour: send request to GzScene3D
if (this->dataPtr->legacy)
{
std::function<void(const ignition::msgs::Boolean &, const bool)> cb =
[](const ignition::msgs::Boolean &/*_rep*/, const bool _result)
{
if (!_result)
ignerr << "Error setting transform mode" << std::endl;
};

ignition::msgs::StringMsg req;
req.set_data(modeStr);
this->dataPtr->node.Request(this->dataPtr->service, req, cb);
Expand Down

0 comments on commit caf08a9

Please sign in to comment.