Skip to content

Commit

Permalink
docs: add a snippet for moving objects in Gazebo
Browse files Browse the repository at this point in the history
  • Loading branch information
okalachev committed Feb 13, 2024
1 parent f91dc4d commit 42c26aa
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 0 deletions.
20 changes: 20 additions & 0 deletions docs/en/snippets.md
Original file line number Diff line number Diff line change
Expand Up @@ -488,3 +488,23 @@ Check, if the code is running inside a [Gazebo simulation](simulation.md):
```python
is_simulation = rospy.get_param('/use_sim_time', False)
```

### # #{simulator-interaction}

You can move a physical object (link) in Gazebo (as well as change its velocity) using the `gazebo/set_link_state` service (of the type [`SetLinkState`](http://docs.ros.org/en/api/gazebo_msgs/html/srv/SetLinkState.html)). For example, if you add a cube to the world (link `unit_box::link`), you can move it to the point (1, 2, 3):

```python
import rospy
from geometry_msgs.msg import Point, Pose, Quaternion
from gazebo_msgs.srv import SetLinkState
from gazebo_msgs.msg import LinkState

rospy.init_node('flight')

set_link_state = rospy.ServiceProxy('gazebo/set_link_state', SetLinkState)

# Change link's position
set_link_state(LinkState(link_name='unit_box::link', pose=Pose(position=Point(1, 2, 3), orientation=Quaternion(0, 0, 0, 1))))
```

> **Info** Simple object animation in Gazebo can be implemented [using actors](http://classic.gazebosim.org/tutorials?tut=actor&cat=build_robot).
20 changes: 20 additions & 0 deletions docs/ru/snippets.md
Original file line number Diff line number Diff line change
Expand Up @@ -499,3 +499,23 @@ param_set(param_id='MPC_Z_P', value=ParamValue(real=1.5))
```python
is_simulation = rospy.get_param('/use_sim_time', False)
```

### # #{simulator-interaction}

Переместить физический объект (линк) в Gazebo (а также поменять его скорости) можно при помощи сервиса `gazebo/set_link_state` (тип [`SetLinkState`](http://docs.ros.org/en/api/gazebo_msgs/html/srv/SetLinkState.html)). Например, если добавить в мир объект куб (линк `unit_box::link`), то так можно переместить его в точку (1, 2, 3):

```python
import rospy
from geometry_msgs.msg import Point, Pose, Quaternion
from gazebo_msgs.srv import SetLinkState
from gazebo_msgs.msg import LinkState

rospy.init_node('flight')

set_link_state = rospy.ServiceProxy('gazebo/set_link_state', SetLinkState)

# Переместить линк в Gazebo
set_link_state(LinkState(link_name='unit_box::link', pose=Pose(position=Point(1, 2, 3), orientation=Quaternion(0, 0, 0, 1))))
```

> **Info** Простую анимацию объектов в Gazebo можно реализовать [с помощью акторов](http://classic.gazebosim.org/tutorials?tut=actor&cat=build_robot).

0 comments on commit 42c26aa

Please sign in to comment.