-
Notifications
You must be signed in to change notification settings - Fork 770
/
gazebo_ros_force_demo.world
81 lines (76 loc) · 2.11 KB
/
gazebo_ros_force_demo.world
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
<?xml version="1.0"?>
<!--
Gazebo ROS force plugin demo
If you want the force to be applied on the world frame, use
<force_frame>world</force_frame>
If you want the force to be applied on the link frame, use
<force_frame>link</force_frame>
Try for example:
ros2 topic pub -1 /demo/world/force_demo geometry_msgs/Wrench "force: {x: 10.0}"
and
ros2 topic pub -1 /demo/link/force_demo geometry_msgs/Wrench "force: {x: 10.0}"
-->
<sdf version="1.6">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="force_on_world_frame">
<pose>0 3 0.5 0 0 1.57</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
</link>
<plugin name="gazebo_ros_force" filename="libgazebo_ros_force.so">
<ros>
<namespace>/demo/world</namespace>
<argument>gazebo_ros_force:=force_demo</argument>
</ros>
<link_name>link</link_name>
<force_frame>world</force_frame>
</plugin>
</model>
<model name="force_on_link_frame">
<pose>0 -3 0.5 0 0 1.57</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
</link>
<plugin name="gazebo_ros_force" filename="libgazebo_ros_force.so">
<ros>
<namespace>/demo/link</namespace>
<argument>gazebo_ros_force:=force_demo</argument>
</ros>
<link_name>link</link_name>
<force_frame>link</force_frame>
</plugin>
</model>
</world>
</sdf>