Skip to content

Commit

Permalink
fix move to model (#2126)
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <ichen@openrobotics.org>
  • Loading branch information
iche033 authored Sep 7, 2023
1 parent 5bb1b1c commit 9055d88
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 6 deletions.
4 changes: 1 addition & 3 deletions src/gui/plugins/view_angle/ViewAngle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -338,9 +338,7 @@ bool ViewAngle::OnMoveToModelService(const gz::msgs::GUICamera &_msg,
Entity entityId = kNullEntity;
try
{
// TODO(ahcorde): When forward porting this to Garder change var type to
// unsigned int
entityId = std::get<int>(visualToMove->UserData("gazebo-entity"));
entityId = std::get<uint64_t>(visualToMove->UserData("gazebo-entity"));
}
catch(std::bad_variant_access &_e)
{
Expand Down
6 changes: 3 additions & 3 deletions tutorials/move_camera_to_model.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,20 +5,20 @@ This tutorial gives an introduction to Gazebo's service `/gui/move_to/model`. Th
## How to move the camera to a model

1. Load the **View Angle** plugin. This service is only available when the **View Angle** plugin is loaded.
2. Call the service using the request message type `ignition.msgs.GUICamera` and the response message type `ignition.msgs.Boolean`. The distance to the object is defined as the z coordinate, and the direction of the camera with a quaternion. It's possible to select the projection type.
2. Call the service using the request message type `gz.msgs.GUICamera` and the response message type `gz.msgs.Boolean`. The distance to the object is defined as the z coordinate, and the direction of the camera with a quaternion. It's possible to select the projection type.

For example, Let's move the camera to the `box` model looking down from 5 meters away.

```bash
ign service -s /gui/move_to/model --reqtype ignition.msgs.GUICamera --reptype ignition.msgs.Boolean -r 'name: "box", pose: {position: {z:5}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000
gz service -s /gui/move_to/model --reqtype gz.msgs.GUICamera --reptype gz.msgs.Boolean -r 'name: "box", pose: {position: {z:5}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000
```

@image html files/move_camera_to_model/box_5.gif

The camera can also be placed far away, for example 20 meters:

```bash
ign service -s /gui/move_to/model --reqtype ignition.msgs.GUICamera --reptype ignition.msgs.Boolean -r 'name: "box", pose: {position: {z:20}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000
gz service -s /gui/move_to/model --reqtype gz.msgs.GUICamera --reptype gz.msgs.Boolean -r 'name: "box", pose: {position: {z:20}, orientation: {x:0, y:0, z: -1, w:0}}, projection_type: "orbit"' --timeout 5000
```

@image html files/move_camera_to_model/box_20.gif
Expand Down

0 comments on commit 9055d88

Please sign in to comment.