-
Notifications
You must be signed in to change notification settings - Fork 770
/
gazebo_ros_planar_move_demo.world
73 lines (57 loc) · 1.68 KB
/
gazebo_ros_planar_move_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
<?xml version="1.0"?>
<!--
Gazebo ROS differential drive plugin demo
Try sending commands:
ros2 topic pub /demo/cmd_demo geometry_msgs/Twist '{linear: {x: 1.0}}' -1
ros2 topic pub /demo/cmd_demo geometry_msgs/Twist '{angular: {z: 0.1}}' -1
Try listening to odometry:
ros2 topic echo /demo/odom_demo
Try listening to TF:
ros2 run tf2_ros tf2_echo odom_demo link
-->
<sdf version="1.6">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="box">
<pose>0 0 0.5 0 0 0</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='planar_move' filename='libgazebo_ros_planar_move.so'>
<ros>
<namespace>/demo</namespace>
<argument>cmd_vel:=cmd_demo</argument>
<argument>odom:=odom_demo</argument>
</ros>
<update_rate>100</update_rate>
<publish_rate>10</publish_rate>
<!-- output -->
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<odometry_frame>odom_demo</odometry_frame>
<robot_base_frame>link</robot_base_frame>
<covariance_x>0.0001</covariance_x>
<covariance_y>0.0001</covariance_y>
<covariance_yaw>0.01</covariance_yaw>
</plugin>
</model>
</world>
</sdf>