agenticros 0.1.0 → 0.1.2
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- package/dist/commands/config.d.ts.map +1 -1
- package/dist/commands/config.js +37 -1
- package/dist/commands/config.js.map +1 -1
- package/dist/commands/down.d.ts +6 -4
- package/dist/commands/down.d.ts.map +1 -1
- package/dist/commands/down.js +16 -6
- package/dist/commands/down.js.map +1 -1
- package/dist/commands/logs.js +2 -2
- package/dist/commands/logs.js.map +1 -1
- package/dist/commands/status.d.ts.map +1 -1
- package/dist/commands/status.js +10 -6
- package/dist/commands/status.js.map +1 -1
- package/dist/commands/up.d.ts +1 -0
- package/dist/commands/up.d.ts.map +1 -1
- package/dist/commands/up.js +33 -1
- package/dist/commands/up.js.map +1 -1
- package/dist/index.js +25 -4
- package/dist/index.js.map +1 -1
- package/dist/runners/sim.d.ts +2 -0
- package/dist/runners/sim.d.ts.map +1 -1
- package/dist/runners/sim.js +2 -0
- package/dist/runners/sim.js.map +1 -1
- package/package.json +1 -1
- package/runtime/BUNDLE.json +1 -1
- package/runtime/packages/core/src/transport/local/transport.ts +25 -5
- package/runtime/ros2_ws/src/agenticros_sim/CMakeLists.txt +25 -0
- package/runtime/ros2_ws/src/agenticros_sim/README.md +120 -0
- package/runtime/ros2_ws/src/agenticros_sim/config/agenticros-sim.config.json +28 -0
- package/runtime/ros2_ws/src/agenticros_sim/config/amr_bridge.yaml +111 -0
- package/runtime/ros2_ws/src/agenticros_sim/config/amr_view.rviz +192 -0
- package/runtime/ros2_ws/src/agenticros_sim/env-hooks/gz_resource_path.dsv.in +3 -0
- package/runtime/ros2_ws/src/agenticros_sim/env-hooks/gz_resource_path.sh.in +7 -0
- package/runtime/ros2_ws/src/agenticros_sim/launch/sim_amr.launch.py +184 -0
- package/runtime/ros2_ws/src/agenticros_sim/models/agenticros_amr/model.config +17 -0
- package/runtime/ros2_ws/src/agenticros_sim/models/agenticros_amr/model.sdf +251 -0
- package/runtime/ros2_ws/src/agenticros_sim/package.xml +27 -0
- package/runtime/ros2_ws/src/agenticros_sim/urdf/agenticros_amr.urdf.xacro +127 -0
- package/runtime/ros2_ws/src/agenticros_sim/worlds/agenticros_indoor.sdf +183 -0
- package/runtime/scripts/configure_for_sim.sh +64 -0
- package/runtime/scripts/sim/run_sim.sh +169 -0
- package/runtime/scripts/test-follow-me-sim.mjs +135 -0
- package/runtime/scripts/test-mcp-e2e.mjs +184 -0
|
@@ -0,0 +1,251 @@
|
|
|
1
|
+
<?xml version="1.0"?>
|
|
2
|
+
<!--
|
|
3
|
+
agenticros_amr/model.sdf
|
|
4
|
+
Two-wheel differential-drive AMR with:
|
|
5
|
+
* Chassis link (rectangular)
|
|
6
|
+
* Two driven wheels + one passive caster
|
|
7
|
+
* Forward-facing RGB-D camera (RealSense D435-ish: 640x480 colour + 16-bit depth)
|
|
8
|
+
* 2D GPU lidar (RPLidar-like, 360°, 12 Hz)
|
|
9
|
+
* IMU
|
|
10
|
+
* gz-sim diff-drive + odometry + joint-state systems
|
|
11
|
+
|
|
12
|
+
Topic layout (Gazebo side; ros_gz_bridge translates to ROS):
|
|
13
|
+
cmd_vel → /model/agenticros_amr/cmd_vel
|
|
14
|
+
odom → /model/agenticros_amr/odometry
|
|
15
|
+
tf → /model/agenticros_amr/tf
|
|
16
|
+
rgb image → /camera/camera/color/image_raw (matches real RealSense)
|
|
17
|
+
rgb camera_info → /camera/camera/color/camera_info
|
|
18
|
+
depth image (16UC1) → /camera/camera/depth/image_rect_raw
|
|
19
|
+
depth camera_info → /camera/camera/depth/camera_info
|
|
20
|
+
lidar scan → /scan
|
|
21
|
+
imu → /imu/data
|
|
22
|
+
-->
|
|
23
|
+
<sdf version="1.10">
|
|
24
|
+
<model name="agenticros_amr">
|
|
25
|
+
|
|
26
|
+
<!-- ===================== Chassis ===================== -->
|
|
27
|
+
<link name="base_link">
|
|
28
|
+
<pose>0 0 0.10 0 0 0</pose>
|
|
29
|
+
<inertial>
|
|
30
|
+
<mass>5.0</mass>
|
|
31
|
+
<inertia>
|
|
32
|
+
<ixx>0.10</ixx><iyy>0.15</iyy><izz>0.20</izz>
|
|
33
|
+
<ixy>0</ixy><ixz>0</ixz><iyz>0</iyz>
|
|
34
|
+
</inertia>
|
|
35
|
+
</inertial>
|
|
36
|
+
<collision name="chassis_col">
|
|
37
|
+
<geometry><box><size>0.40 0.30 0.15</size></box></geometry>
|
|
38
|
+
</collision>
|
|
39
|
+
<visual name="chassis_vis">
|
|
40
|
+
<geometry><box><size>0.40 0.30 0.15</size></box></geometry>
|
|
41
|
+
<material><ambient>0.2 0.2 0.25 1</ambient><diffuse>0.3 0.3 0.35 1</diffuse></material>
|
|
42
|
+
</visual>
|
|
43
|
+
|
|
44
|
+
<!-- ============ RealSense-D435-like depth camera ============ -->
|
|
45
|
+
<!--
|
|
46
|
+
Mounted at front of the chassis, 0.10 m above the chassis top, looking
|
|
47
|
+
forward (+X). HFOV 87° matches the real D435 depth sensor; FOLLOW_ME
|
|
48
|
+
depth-loop code already assumes this HFOV constant.
|
|
49
|
+
-->
|
|
50
|
+
<sensor name="depth_camera" type="rgbd_camera">
|
|
51
|
+
<pose>0.20 0 0.18 0 0 0</pose>
|
|
52
|
+
<topic>camera</topic>
|
|
53
|
+
<update_rate>30</update_rate>
|
|
54
|
+
<camera>
|
|
55
|
+
<horizontal_fov>1.5184</horizontal_fov>
|
|
56
|
+
<image>
|
|
57
|
+
<width>640</width>
|
|
58
|
+
<height>480</height>
|
|
59
|
+
<format>R8G8B8</format>
|
|
60
|
+
</image>
|
|
61
|
+
<clip>
|
|
62
|
+
<near>0.10</near>
|
|
63
|
+
<far>10.0</far>
|
|
64
|
+
</clip>
|
|
65
|
+
<distortion>
|
|
66
|
+
<k1>0.0</k1><k2>0.0</k2><k3>0.0</k3><p1>0.0</p1><p2>0.0</p2>
|
|
67
|
+
</distortion>
|
|
68
|
+
<optical_frame_id>camera_optical_link</optical_frame_id>
|
|
69
|
+
<depth_camera>
|
|
70
|
+
<output>depths</output>
|
|
71
|
+
</depth_camera>
|
|
72
|
+
</camera>
|
|
73
|
+
<always_on>true</always_on>
|
|
74
|
+
<visualize>false</visualize>
|
|
75
|
+
</sensor>
|
|
76
|
+
|
|
77
|
+
<!-- ============ 2D GPU lidar (RPLidar-ish) ============ -->
|
|
78
|
+
<sensor name="gpu_lidar" type="gpu_lidar">
|
|
79
|
+
<pose>0 0 0.20 0 0 0</pose>
|
|
80
|
+
<topic>scan</topic>
|
|
81
|
+
<update_rate>12</update_rate>
|
|
82
|
+
<lidar>
|
|
83
|
+
<scan>
|
|
84
|
+
<horizontal>
|
|
85
|
+
<samples>360</samples>
|
|
86
|
+
<resolution>1</resolution>
|
|
87
|
+
<min_angle>-3.14159</min_angle>
|
|
88
|
+
<max_angle>3.14159</max_angle>
|
|
89
|
+
</horizontal>
|
|
90
|
+
</scan>
|
|
91
|
+
<range>
|
|
92
|
+
<min>0.10</min>
|
|
93
|
+
<max>12.0</max>
|
|
94
|
+
<resolution>0.01</resolution>
|
|
95
|
+
</range>
|
|
96
|
+
<noise>
|
|
97
|
+
<type>gaussian</type><mean>0.0</mean><stddev>0.01</stddev>
|
|
98
|
+
</noise>
|
|
99
|
+
<frame_id>lidar_link</frame_id>
|
|
100
|
+
</lidar>
|
|
101
|
+
<always_on>true</always_on>
|
|
102
|
+
<visualize>false</visualize>
|
|
103
|
+
</sensor>
|
|
104
|
+
|
|
105
|
+
<!-- ============ IMU ============ -->
|
|
106
|
+
<sensor name="imu_sensor" type="imu">
|
|
107
|
+
<pose>0 0 0 0 0 0</pose>
|
|
108
|
+
<topic>imu</topic>
|
|
109
|
+
<update_rate>100</update_rate>
|
|
110
|
+
<imu>
|
|
111
|
+
<angular_velocity>
|
|
112
|
+
<x><noise type="gaussian"><mean>0.0</mean><stddev>0.0005</stddev></noise></x>
|
|
113
|
+
<y><noise type="gaussian"><mean>0.0</mean><stddev>0.0005</stddev></noise></y>
|
|
114
|
+
<z><noise type="gaussian"><mean>0.0</mean><stddev>0.0005</stddev></noise></z>
|
|
115
|
+
</angular_velocity>
|
|
116
|
+
<linear_acceleration>
|
|
117
|
+
<x><noise type="gaussian"><mean>0.0</mean><stddev>0.005</stddev></noise></x>
|
|
118
|
+
<y><noise type="gaussian"><mean>0.0</mean><stddev>0.005</stddev></noise></y>
|
|
119
|
+
<z><noise type="gaussian"><mean>0.0</mean><stddev>0.005</stddev></noise></z>
|
|
120
|
+
</linear_acceleration>
|
|
121
|
+
</imu>
|
|
122
|
+
<always_on>true</always_on>
|
|
123
|
+
</sensor>
|
|
124
|
+
</link>
|
|
125
|
+
|
|
126
|
+
<!-- ===================== Left wheel ===================== -->
|
|
127
|
+
<link name="left_wheel_link">
|
|
128
|
+
<pose>0 0.18 0.08 -1.5707 0 0</pose>
|
|
129
|
+
<inertial>
|
|
130
|
+
<mass>0.5</mass>
|
|
131
|
+
<inertia><ixx>0.0008</ixx><iyy>0.0008</iyy><izz>0.0015</izz><ixy>0</ixy><ixz>0</ixz><iyz>0</iyz></inertia>
|
|
132
|
+
</inertial>
|
|
133
|
+
<collision name="col">
|
|
134
|
+
<geometry><cylinder><radius>0.08</radius><length>0.04</length></cylinder></geometry>
|
|
135
|
+
<surface><friction><ode><mu>1.0</mu><mu2>1.0</mu2></ode></friction></surface>
|
|
136
|
+
</collision>
|
|
137
|
+
<visual name="vis">
|
|
138
|
+
<geometry><cylinder><radius>0.08</radius><length>0.04</length></cylinder></geometry>
|
|
139
|
+
<material><ambient>0.1 0.1 0.1 1</ambient><diffuse>0.15 0.15 0.15 1</diffuse></material>
|
|
140
|
+
</visual>
|
|
141
|
+
</link>
|
|
142
|
+
|
|
143
|
+
<!-- ===================== Right wheel ===================== -->
|
|
144
|
+
<link name="right_wheel_link">
|
|
145
|
+
<pose>0 -0.18 0.08 -1.5707 0 0</pose>
|
|
146
|
+
<inertial>
|
|
147
|
+
<mass>0.5</mass>
|
|
148
|
+
<inertia><ixx>0.0008</ixx><iyy>0.0008</iyy><izz>0.0015</izz><ixy>0</ixy><ixz>0</ixz><iyz>0</iyz></inertia>
|
|
149
|
+
</inertial>
|
|
150
|
+
<collision name="col">
|
|
151
|
+
<geometry><cylinder><radius>0.08</radius><length>0.04</length></cylinder></geometry>
|
|
152
|
+
<surface><friction><ode><mu>1.0</mu><mu2>1.0</mu2></ode></friction></surface>
|
|
153
|
+
</collision>
|
|
154
|
+
<visual name="vis">
|
|
155
|
+
<geometry><cylinder><radius>0.08</radius><length>0.04</length></cylinder></geometry>
|
|
156
|
+
<material><ambient>0.1 0.1 0.1 1</ambient><diffuse>0.15 0.15 0.15 1</diffuse></material>
|
|
157
|
+
</visual>
|
|
158
|
+
</link>
|
|
159
|
+
|
|
160
|
+
<!-- ===================== Caster (passive front wheel) ===================== -->
|
|
161
|
+
<link name="caster_link">
|
|
162
|
+
<pose>0.16 0 0.04 0 0 0</pose>
|
|
163
|
+
<inertial>
|
|
164
|
+
<mass>0.1</mass>
|
|
165
|
+
<inertia><ixx>0.00004</ixx><iyy>0.00004</iyy><izz>0.00004</izz><ixy>0</ixy><ixz>0</ixz><iyz>0</iyz></inertia>
|
|
166
|
+
</inertial>
|
|
167
|
+
<collision name="col">
|
|
168
|
+
<geometry><sphere><radius>0.04</radius></sphere></geometry>
|
|
169
|
+
<surface><friction><ode><mu>0.05</mu><mu2>0.05</mu2></ode></friction></surface>
|
|
170
|
+
</collision>
|
|
171
|
+
<visual name="vis">
|
|
172
|
+
<geometry><sphere><radius>0.04</radius></sphere></geometry>
|
|
173
|
+
<material><ambient>0.1 0.1 0.1 1</ambient><diffuse>0.15 0.15 0.15 1</diffuse></material>
|
|
174
|
+
</visual>
|
|
175
|
+
</link>
|
|
176
|
+
|
|
177
|
+
<!-- ===================== Joints ===================== -->
|
|
178
|
+
<joint name="left_wheel_joint" type="revolute">
|
|
179
|
+
<parent>base_link</parent>
|
|
180
|
+
<child>left_wheel_link</child>
|
|
181
|
+
<axis>
|
|
182
|
+
<xyz>0 0 1</xyz>
|
|
183
|
+
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
|
|
184
|
+
</axis>
|
|
185
|
+
</joint>
|
|
186
|
+
|
|
187
|
+
<joint name="right_wheel_joint" type="revolute">
|
|
188
|
+
<parent>base_link</parent>
|
|
189
|
+
<child>right_wheel_link</child>
|
|
190
|
+
<axis>
|
|
191
|
+
<xyz>0 0 1</xyz>
|
|
192
|
+
<limit><lower>-1e16</lower><upper>1e16</upper></limit>
|
|
193
|
+
</axis>
|
|
194
|
+
</joint>
|
|
195
|
+
|
|
196
|
+
<joint name="caster_joint" type="ball">
|
|
197
|
+
<parent>base_link</parent>
|
|
198
|
+
<child>caster_link</child>
|
|
199
|
+
</joint>
|
|
200
|
+
|
|
201
|
+
<!-- ===================== Plugins ===================== -->
|
|
202
|
+
<!--
|
|
203
|
+
Differential drive: subscribes to /model/agenticros_amr/cmd_vel and drives
|
|
204
|
+
the wheels. Publishes /model/agenticros_amr/odometry and tf as gz topics
|
|
205
|
+
that the bridge re-emits as ROS topics.
|
|
206
|
+
-->
|
|
207
|
+
<plugin filename="gz-sim-diff-drive-system" name="gz::sim::systems::DiffDrive">
|
|
208
|
+
<left_joint>left_wheel_joint</left_joint>
|
|
209
|
+
<right_joint>right_wheel_joint</right_joint>
|
|
210
|
+
<wheel_separation>0.36</wheel_separation>
|
|
211
|
+
<wheel_radius>0.08</wheel_radius>
|
|
212
|
+
<odom_publish_frequency>50</odom_publish_frequency>
|
|
213
|
+
<!--
|
|
214
|
+
Intentionally NOT setting <topic> so gz-sim uses its documented default
|
|
215
|
+
of /model/<model_name>/cmd_vel. The bridge in config/amr_bridge.yaml
|
|
216
|
+
publishes there, so plugin and bridge agree.
|
|
217
|
+
Previously had <topic>cmd_vel</topic> which gz interpreted as a
|
|
218
|
+
relative/no-namespace topic and bound to /cmd_vel - the bridge then
|
|
219
|
+
published into a void and the robot never moved.
|
|
220
|
+
-->
|
|
221
|
+
<odom_topic>odometry</odom_topic>
|
|
222
|
+
<tf_topic>tf</tf_topic>
|
|
223
|
+
<frame_id>odom</frame_id>
|
|
224
|
+
<child_frame_id>base_link</child_frame_id>
|
|
225
|
+
<max_linear_acceleration>1.0</max_linear_acceleration>
|
|
226
|
+
<max_angular_acceleration>2.0</max_angular_acceleration>
|
|
227
|
+
</plugin>
|
|
228
|
+
|
|
229
|
+
<plugin filename="gz-sim-joint-state-publisher-system" name="gz::sim::systems::JointStatePublisher">
|
|
230
|
+
<topic>joint_states</topic>
|
|
231
|
+
</plugin>
|
|
232
|
+
|
|
233
|
+
<!--
|
|
234
|
+
Pose publisher: every link's pose relative to the world. Useful for RViz
|
|
235
|
+
visualization without running robot_state_publisher with a URDF — but
|
|
236
|
+
note ROS tools generally expect /tf, which the diff-drive plugin
|
|
237
|
+
provides for the base + odom relationship.
|
|
238
|
+
-->
|
|
239
|
+
<plugin filename="gz-sim-pose-publisher-system" name="gz::sim::systems::PosePublisher">
|
|
240
|
+
<publish_link_pose>true</publish_link_pose>
|
|
241
|
+
<publish_sensor_pose>true</publish_sensor_pose>
|
|
242
|
+
<publish_collision_pose>false</publish_collision_pose>
|
|
243
|
+
<publish_visual_pose>false</publish_visual_pose>
|
|
244
|
+
<publish_nested_model_pose>false</publish_nested_model_pose>
|
|
245
|
+
<use_pose_vector_msg>true</use_pose_vector_msg>
|
|
246
|
+
<static_publisher>true</static_publisher>
|
|
247
|
+
<static_update_frequency>1</static_update_frequency>
|
|
248
|
+
</plugin>
|
|
249
|
+
|
|
250
|
+
</model>
|
|
251
|
+
</sdf>
|
|
@@ -0,0 +1,27 @@
|
|
|
1
|
+
<?xml version="1.0"?>
|
|
2
|
+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
|
3
|
+
<package format="3">
|
|
4
|
+
<name>agenticros_sim</name>
|
|
5
|
+
<version>0.1.0</version>
|
|
6
|
+
<description>
|
|
7
|
+
AgenticROS Gazebo Harmonic simulation assets: indoor world, 2-wheel AMR
|
|
8
|
+
model (depth camera + GPU lidar + IMU), ros_gz_bridge config that exposes
|
|
9
|
+
topics on AgenticROS' real-robot topic names, and a launch file that wires
|
|
10
|
+
it all together. Use with the agenticros CLI: agenticros up sim-amr.
|
|
11
|
+
</description>
|
|
12
|
+
<maintainer email="hello@plaipin.com">PlaiPin</maintainer>
|
|
13
|
+
<license>Apache-2.0</license>
|
|
14
|
+
|
|
15
|
+
<buildtool_depend>ament_cmake</buildtool_depend>
|
|
16
|
+
|
|
17
|
+
<exec_depend>ros_gz_sim</exec_depend>
|
|
18
|
+
<exec_depend>ros_gz_bridge</exec_depend>
|
|
19
|
+
<exec_depend>ros_gz_image</exec_depend>
|
|
20
|
+
<exec_depend>robot_state_publisher</exec_depend>
|
|
21
|
+
<exec_depend>xacro</exec_depend>
|
|
22
|
+
<exec_depend>rviz2</exec_depend>
|
|
23
|
+
|
|
24
|
+
<export>
|
|
25
|
+
<build_type>ament_cmake</build_type>
|
|
26
|
+
</export>
|
|
27
|
+
</package>
|
|
@@ -0,0 +1,127 @@
|
|
|
1
|
+
<?xml version="1.0"?>
|
|
2
|
+
<!--
|
|
3
|
+
agenticros_amr.urdf.xacro
|
|
4
|
+
|
|
5
|
+
URDF mirror of models/agenticros_amr/model.sdf, used by robot_state_publisher
|
|
6
|
+
so RViz's RobotModel display can render a 3D mesh of the AMR. Dimensions and
|
|
7
|
+
pose offsets match the SDF exactly:
|
|
8
|
+
* base_link: 0.40 x 0.30 x 0.15 m box, mounted at z=0.10 m above ground
|
|
9
|
+
* wheels: 0.08 m radius, 0.04 m thickness, at ±0.18 m y, z=0.08 m
|
|
10
|
+
* caster: 0.04 m sphere at x=0.16, z=0.04
|
|
11
|
+
* depth camera at x=0.20, z=0.20 (front of chassis, top)
|
|
12
|
+
* 2D lidar at z=0.30 (above chassis)
|
|
13
|
+
|
|
14
|
+
The wheel joints are continuous so /joint_states updates wheel spin when the
|
|
15
|
+
diff-drive plugin publishes joint angles via the JointStatePublisher system.
|
|
16
|
+
|
|
17
|
+
Note: This is purely for visualization. The physics, sensors, and actuators
|
|
18
|
+
all live in the SDF that Gazebo loads.
|
|
19
|
+
-->
|
|
20
|
+
<robot name="agenticros_amr" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
21
|
+
|
|
22
|
+
<!-- ===================== base_link ===================== -->
|
|
23
|
+
<link name="base_link">
|
|
24
|
+
<visual>
|
|
25
|
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
26
|
+
<geometry><box size="0.40 0.30 0.15"/></geometry>
|
|
27
|
+
<material name="chassis_grey"><color rgba="0.3 0.3 0.35 1"/></material>
|
|
28
|
+
</visual>
|
|
29
|
+
<collision>
|
|
30
|
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
31
|
+
<geometry><box size="0.40 0.30 0.15"/></geometry>
|
|
32
|
+
</collision>
|
|
33
|
+
<inertial>
|
|
34
|
+
<mass value="5.0"/>
|
|
35
|
+
<inertia ixx="0.10" iyy="0.15" izz="0.20" ixy="0" ixz="0" iyz="0"/>
|
|
36
|
+
</inertial>
|
|
37
|
+
</link>
|
|
38
|
+
|
|
39
|
+
<!-- ===================== Wheels ===================== -->
|
|
40
|
+
<!-- xacro provides ${pi} as a built-in property; don't redefine it. -->
|
|
41
|
+
<xacro:macro name="wheel" params="prefix y_offset">
|
|
42
|
+
<link name="${prefix}_wheel_link">
|
|
43
|
+
<visual>
|
|
44
|
+
<origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
|
|
45
|
+
<geometry><cylinder radius="0.08" length="0.04"/></geometry>
|
|
46
|
+
<material name="wheel_black"><color rgba="0.15 0.15 0.15 1"/></material>
|
|
47
|
+
</visual>
|
|
48
|
+
<collision>
|
|
49
|
+
<origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
|
|
50
|
+
<geometry><cylinder radius="0.08" length="0.04"/></geometry>
|
|
51
|
+
</collision>
|
|
52
|
+
<inertial>
|
|
53
|
+
<mass value="0.5"/>
|
|
54
|
+
<inertia ixx="0.0008" iyy="0.0008" izz="0.0015" ixy="0" ixz="0" iyz="0"/>
|
|
55
|
+
</inertial>
|
|
56
|
+
</link>
|
|
57
|
+
<joint name="${prefix}_wheel_joint" type="continuous">
|
|
58
|
+
<parent link="base_link"/>
|
|
59
|
+
<child link="${prefix}_wheel_link"/>
|
|
60
|
+
<origin xyz="0 ${y_offset} -0.02" rpy="0 0 0"/>
|
|
61
|
+
<axis xyz="0 1 0"/>
|
|
62
|
+
</joint>
|
|
63
|
+
</xacro:macro>
|
|
64
|
+
<xacro:wheel prefix="left" y_offset="0.18"/>
|
|
65
|
+
<xacro:wheel prefix="right" y_offset="-0.18"/>
|
|
66
|
+
|
|
67
|
+
<!-- ===================== Caster ===================== -->
|
|
68
|
+
<link name="caster_link">
|
|
69
|
+
<visual>
|
|
70
|
+
<geometry><sphere radius="0.04"/></geometry>
|
|
71
|
+
<material name="wheel_black"/>
|
|
72
|
+
</visual>
|
|
73
|
+
<collision>
|
|
74
|
+
<geometry><sphere radius="0.04"/></geometry>
|
|
75
|
+
</collision>
|
|
76
|
+
<inertial>
|
|
77
|
+
<mass value="0.1"/>
|
|
78
|
+
<inertia ixx="0.00004" iyy="0.00004" izz="0.00004" ixy="0" ixz="0" iyz="0"/>
|
|
79
|
+
</inertial>
|
|
80
|
+
</link>
|
|
81
|
+
<joint name="caster_joint" type="fixed">
|
|
82
|
+
<parent link="base_link"/>
|
|
83
|
+
<child link="caster_link"/>
|
|
84
|
+
<origin xyz="0.16 0 -0.06" rpy="0 0 0"/>
|
|
85
|
+
</joint>
|
|
86
|
+
|
|
87
|
+
<!-- ===================== Depth camera ===================== -->
|
|
88
|
+
<link name="camera_link">
|
|
89
|
+
<visual>
|
|
90
|
+
<geometry><box size="0.025 0.09 0.025"/></geometry>
|
|
91
|
+
<material name="camera_alu"><color rgba="0.1 0.1 0.15 1"/></material>
|
|
92
|
+
</visual>
|
|
93
|
+
</link>
|
|
94
|
+
<joint name="camera_joint" type="fixed">
|
|
95
|
+
<parent link="base_link"/>
|
|
96
|
+
<child link="camera_link"/>
|
|
97
|
+
<origin xyz="0.20 0 0.10" rpy="0 0 0"/>
|
|
98
|
+
</joint>
|
|
99
|
+
<!-- Optical frame: REP-103 (z forward, x right, y down) used by image topics -->
|
|
100
|
+
<link name="camera_optical_link"/>
|
|
101
|
+
<joint name="camera_optical_joint" type="fixed">
|
|
102
|
+
<parent link="camera_link"/>
|
|
103
|
+
<child link="camera_optical_link"/>
|
|
104
|
+
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
|
105
|
+
</joint>
|
|
106
|
+
|
|
107
|
+
<!-- ===================== 2D LiDAR ===================== -->
|
|
108
|
+
<link name="lidar_link">
|
|
109
|
+
<visual>
|
|
110
|
+
<geometry><cylinder radius="0.04" length="0.04"/></geometry>
|
|
111
|
+
<material name="lidar_white"><color rgba="0.9 0.9 0.9 1"/></material>
|
|
112
|
+
</visual>
|
|
113
|
+
</link>
|
|
114
|
+
<joint name="lidar_joint" type="fixed">
|
|
115
|
+
<parent link="base_link"/>
|
|
116
|
+
<child link="lidar_link"/>
|
|
117
|
+
<origin xyz="0 0 0.10" rpy="0 0 0"/>
|
|
118
|
+
</joint>
|
|
119
|
+
|
|
120
|
+
<!-- ===================== IMU ===================== -->
|
|
121
|
+
<link name="imu_link"/>
|
|
122
|
+
<joint name="imu_joint" type="fixed">
|
|
123
|
+
<parent link="base_link"/>
|
|
124
|
+
<child link="imu_link"/>
|
|
125
|
+
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
126
|
+
</joint>
|
|
127
|
+
</robot>
|
|
@@ -0,0 +1,183 @@
|
|
|
1
|
+
<?xml version="1.0"?>
|
|
2
|
+
<!--
|
|
3
|
+
agenticros_indoor.sdf
|
|
4
|
+
Gazebo Harmonic 8.x indoor environment for testing AgenticROS' sim AMR.
|
|
5
|
+
|
|
6
|
+
Layout:
|
|
7
|
+
* 12 m x 12 m floor with subtle walls (so SLAM-style demos have something
|
|
8
|
+
to localize against)
|
|
9
|
+
* Three free-standing cylinder + box obstacles inside the room so the
|
|
10
|
+
depth camera and LIDAR see non-trivial data
|
|
11
|
+
* One human-sized cylinder labeled "person" near the center — used by the
|
|
12
|
+
ros2_follow_me smoke test
|
|
13
|
+
* Standard physics + sensors + ros_gz system plugins so the AMR's depth
|
|
14
|
+
camera / IMU / lidar publish on Gazebo topics that the bridge picks up
|
|
15
|
+
-->
|
|
16
|
+
<sdf version="1.10">
|
|
17
|
+
<world name="agenticros_indoor">
|
|
18
|
+
|
|
19
|
+
<!-- ====== System plugins ====== -->
|
|
20
|
+
<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics"/>
|
|
21
|
+
<plugin filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors">
|
|
22
|
+
<render_engine>ogre2</render_engine>
|
|
23
|
+
</plugin>
|
|
24
|
+
<plugin filename="gz-sim-user-commands-system" name="gz::sim::systems::UserCommands"/>
|
|
25
|
+
<plugin filename="gz-sim-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster"/>
|
|
26
|
+
<plugin filename="gz-sim-imu-system" name="gz::sim::systems::Imu"/>
|
|
27
|
+
|
|
28
|
+
<gravity>0 0 -9.81</gravity>
|
|
29
|
+
|
|
30
|
+
<gui fullscreen="false">
|
|
31
|
+
<plugin filename="MinimalScene" name="3D View">
|
|
32
|
+
<gz-gui>
|
|
33
|
+
<title>3D View</title>
|
|
34
|
+
<property type="bool" key="showTitleBar">false</property>
|
|
35
|
+
<property type="string" key="state">docked</property>
|
|
36
|
+
</gz-gui>
|
|
37
|
+
<engine>ogre2</engine>
|
|
38
|
+
<scene>scene</scene>
|
|
39
|
+
<ambient_light>0.4 0.4 0.4</ambient_light>
|
|
40
|
+
<background_color>0.8 0.8 0.8</background_color>
|
|
41
|
+
<camera_pose>-7 -7 6 0 0.6 0.78</camera_pose>
|
|
42
|
+
</plugin>
|
|
43
|
+
</gui>
|
|
44
|
+
|
|
45
|
+
<!-- ====== Lighting ====== -->
|
|
46
|
+
<light type="directional" name="sun">
|
|
47
|
+
<cast_shadows>true</cast_shadows>
|
|
48
|
+
<pose>0 0 10 0 0 0</pose>
|
|
49
|
+
<diffuse>0.9 0.9 0.9 1</diffuse>
|
|
50
|
+
<specular>0.2 0.2 0.2 1</specular>
|
|
51
|
+
<direction>-0.3 0.2 -0.9</direction>
|
|
52
|
+
</light>
|
|
53
|
+
|
|
54
|
+
<!-- ====== Ground ====== -->
|
|
55
|
+
<model name="ground_plane">
|
|
56
|
+
<static>true</static>
|
|
57
|
+
<link name="link">
|
|
58
|
+
<collision name="collision">
|
|
59
|
+
<geometry><plane><normal>0 0 1</normal><size>20 20</size></plane></geometry>
|
|
60
|
+
</collision>
|
|
61
|
+
<visual name="visual">
|
|
62
|
+
<geometry><plane><normal>0 0 1</normal><size>20 20</size></plane></geometry>
|
|
63
|
+
<material>
|
|
64
|
+
<ambient>0.6 0.6 0.6 1</ambient>
|
|
65
|
+
<diffuse>0.75 0.75 0.75 1</diffuse>
|
|
66
|
+
<specular>0.05 0.05 0.05 1</specular>
|
|
67
|
+
</material>
|
|
68
|
+
</visual>
|
|
69
|
+
</link>
|
|
70
|
+
</model>
|
|
71
|
+
|
|
72
|
+
<!-- ====== Walls (12m x 12m room, 2.5m tall, 0.15m thick) ====== -->
|
|
73
|
+
<model name="walls">
|
|
74
|
+
<static>true</static>
|
|
75
|
+
<link name="link">
|
|
76
|
+
<!-- North wall (+Y) -->
|
|
77
|
+
<collision name="north_col">
|
|
78
|
+
<pose>0 6 1.25 0 0 0</pose>
|
|
79
|
+
<geometry><box><size>12 0.15 2.5</size></box></geometry>
|
|
80
|
+
</collision>
|
|
81
|
+
<visual name="north_vis">
|
|
82
|
+
<pose>0 6 1.25 0 0 0</pose>
|
|
83
|
+
<geometry><box><size>12 0.15 2.5</size></box></geometry>
|
|
84
|
+
<material><ambient>0.85 0.85 0.9 1</ambient><diffuse>0.9 0.9 0.95 1</diffuse></material>
|
|
85
|
+
</visual>
|
|
86
|
+
<!-- South wall (-Y) -->
|
|
87
|
+
<collision name="south_col">
|
|
88
|
+
<pose>0 -6 1.25 0 0 0</pose>
|
|
89
|
+
<geometry><box><size>12 0.15 2.5</size></box></geometry>
|
|
90
|
+
</collision>
|
|
91
|
+
<visual name="south_vis">
|
|
92
|
+
<pose>0 -6 1.25 0 0 0</pose>
|
|
93
|
+
<geometry><box><size>12 0.15 2.5</size></box></geometry>
|
|
94
|
+
<material><ambient>0.85 0.85 0.9 1</ambient><diffuse>0.9 0.9 0.95 1</diffuse></material>
|
|
95
|
+
</visual>
|
|
96
|
+
<!-- East wall (+X) -->
|
|
97
|
+
<collision name="east_col">
|
|
98
|
+
<pose>6 0 1.25 0 0 0</pose>
|
|
99
|
+
<geometry><box><size>0.15 12 2.5</size></box></geometry>
|
|
100
|
+
</collision>
|
|
101
|
+
<visual name="east_vis">
|
|
102
|
+
<pose>6 0 1.25 0 0 0</pose>
|
|
103
|
+
<geometry><box><size>0.15 12 2.5</size></box></geometry>
|
|
104
|
+
<material><ambient>0.85 0.85 0.9 1</ambient><diffuse>0.9 0.9 0.95 1</diffuse></material>
|
|
105
|
+
</visual>
|
|
106
|
+
<!-- West wall (-X) -->
|
|
107
|
+
<collision name="west_col">
|
|
108
|
+
<pose>-6 0 1.25 0 0 0</pose>
|
|
109
|
+
<geometry><box><size>0.15 12 2.5</size></box></geometry>
|
|
110
|
+
</collision>
|
|
111
|
+
<visual name="west_vis">
|
|
112
|
+
<pose>-6 0 1.25 0 0 0</pose>
|
|
113
|
+
<geometry><box><size>0.15 12 2.5</size></box></geometry>
|
|
114
|
+
<material><ambient>0.85 0.85 0.9 1</ambient><diffuse>0.9 0.9 0.95 1</diffuse></material>
|
|
115
|
+
</visual>
|
|
116
|
+
</link>
|
|
117
|
+
</model>
|
|
118
|
+
|
|
119
|
+
<!-- ====== Person-sized cylinder (for ros2_follow_me depth-mode smoke test) ====== -->
|
|
120
|
+
<!--
|
|
121
|
+
Roughly human-shaped: 0.35 m radius, 1.7 m tall, centered ~2.5 m in front
|
|
122
|
+
of the AMR's spawn pose (the AMR spawns at origin facing +X by default).
|
|
123
|
+
-->
|
|
124
|
+
<model name="person_target">
|
|
125
|
+
<!-- Static so it doesn't drift or topple when nudged by the AMR. The
|
|
126
|
+
follow-me smoke test just needs a person-sized object in front of
|
|
127
|
+
the spawn pose; dynamics would make the smoke test flaky. -->
|
|
128
|
+
<static>true</static>
|
|
129
|
+
<pose>2.5 0 0.85 0 0 0</pose>
|
|
130
|
+
<link name="link">
|
|
131
|
+
<inertial>
|
|
132
|
+
<mass>60</mass>
|
|
133
|
+
<inertia><ixx>14.7</ixx><iyy>14.7</iyy><izz>3.7</izz><ixy>0</ixy><ixz>0</ixz><iyz>0</iyz></inertia>
|
|
134
|
+
</inertial>
|
|
135
|
+
<collision name="collision">
|
|
136
|
+
<geometry><cylinder><radius>0.35</radius><length>1.7</length></cylinder></geometry>
|
|
137
|
+
</collision>
|
|
138
|
+
<visual name="visual">
|
|
139
|
+
<geometry><cylinder><radius>0.35</radius><length>1.7</length></cylinder></geometry>
|
|
140
|
+
<material><ambient>0.7 0.4 0.3 1</ambient><diffuse>0.8 0.5 0.4 1</diffuse></material>
|
|
141
|
+
</visual>
|
|
142
|
+
</link>
|
|
143
|
+
</model>
|
|
144
|
+
|
|
145
|
+
<!-- ====== A few static obstacles to give the LIDAR / depth camera structure ====== -->
|
|
146
|
+
<model name="obstacle_box_1">
|
|
147
|
+
<static>true</static>
|
|
148
|
+
<pose>3 -2.5 0.4 0 0 0</pose>
|
|
149
|
+
<link name="link">
|
|
150
|
+
<collision name="c"><geometry><box><size>0.8 0.8 0.8</size></box></geometry></collision>
|
|
151
|
+
<visual name="v">
|
|
152
|
+
<geometry><box><size>0.8 0.8 0.8</size></box></geometry>
|
|
153
|
+
<material><ambient>0.3 0.5 0.7 1</ambient><diffuse>0.3 0.5 0.7 1</diffuse></material>
|
|
154
|
+
</visual>
|
|
155
|
+
</link>
|
|
156
|
+
</model>
|
|
157
|
+
|
|
158
|
+
<model name="obstacle_cyl_1">
|
|
159
|
+
<static>true</static>
|
|
160
|
+
<pose>-2 2.5 0.6 0 0 0</pose>
|
|
161
|
+
<link name="link">
|
|
162
|
+
<collision name="c"><geometry><cylinder><radius>0.35</radius><length>1.2</length></cylinder></geometry></collision>
|
|
163
|
+
<visual name="v">
|
|
164
|
+
<geometry><cylinder><radius>0.35</radius><length>1.2</length></cylinder></geometry>
|
|
165
|
+
<material><ambient>0.7 0.6 0.2 1</ambient><diffuse>0.8 0.7 0.2 1</diffuse></material>
|
|
166
|
+
</visual>
|
|
167
|
+
</link>
|
|
168
|
+
</model>
|
|
169
|
+
|
|
170
|
+
<model name="obstacle_box_2">
|
|
171
|
+
<static>true</static>
|
|
172
|
+
<pose>-3.5 -3 0.3 0 0 0</pose>
|
|
173
|
+
<link name="link">
|
|
174
|
+
<collision name="c"><geometry><box><size>1.2 0.6 0.6</size></box></geometry></collision>
|
|
175
|
+
<visual name="v">
|
|
176
|
+
<geometry><box><size>1.2 0.6 0.6</size></box></geometry>
|
|
177
|
+
<material><ambient>0.3 0.7 0.4 1</ambient><diffuse>0.3 0.8 0.4 1</diffuse></material>
|
|
178
|
+
</visual>
|
|
179
|
+
</link>
|
|
180
|
+
</model>
|
|
181
|
+
|
|
182
|
+
</world>
|
|
183
|
+
</sdf>
|
|
@@ -0,0 +1,64 @@
|
|
|
1
|
+
#!/usr/bin/env bash
|
|
2
|
+
# configure_for_sim.sh
|
|
3
|
+
#
|
|
4
|
+
# One-shot helper: copy the simulation-tuned AgenticROS config template into
|
|
5
|
+
# ~/.agenticros/config.json. Use this when you want the MCP server + OpenClaw
|
|
6
|
+
# plugin to talk to the sim AMR's topics (which use no robot-namespace
|
|
7
|
+
# prefix - so a fresh "real robot" config with a UUID namespace would miss
|
|
8
|
+
# every topic).
|
|
9
|
+
#
|
|
10
|
+
# Usage:
|
|
11
|
+
# ./scripts/configure_for_sim.sh # writes ~/.agenticros/config.json
|
|
12
|
+
# ./scripts/configure_for_sim.sh --backup # back up an existing config first
|
|
13
|
+
# ./scripts/configure_for_sim.sh --print # print the template to stdout
|
|
14
|
+
#
|
|
15
|
+
# After running, restart the MCP server (or run `agenticros up sim-amr`).
|
|
16
|
+
|
|
17
|
+
set -euo pipefail
|
|
18
|
+
|
|
19
|
+
ROOT="$(cd "$(dirname "${BASH_SOURCE[0]}")/.." && pwd)"
|
|
20
|
+
SRC="$ROOT/ros2_ws/src/agenticros_sim/config/agenticros-sim.config.json"
|
|
21
|
+
DEST_DIR="$HOME/.agenticros"
|
|
22
|
+
DEST="$DEST_DIR/config.json"
|
|
23
|
+
|
|
24
|
+
PRINT_ONLY=false
|
|
25
|
+
DO_BACKUP=false
|
|
26
|
+
|
|
27
|
+
while [[ $# -gt 0 ]]; do
|
|
28
|
+
case "$1" in
|
|
29
|
+
--print) PRINT_ONLY=true; shift ;;
|
|
30
|
+
--backup) DO_BACKUP=true; shift ;;
|
|
31
|
+
-h|--help) sed -n '2,16p' "${BASH_SOURCE[0]}" | sed 's/^# \{0,1\}//'; exit 0 ;;
|
|
32
|
+
*) echo "Unknown arg: $1" >&2; exit 2 ;;
|
|
33
|
+
esac
|
|
34
|
+
done
|
|
35
|
+
|
|
36
|
+
if [[ ! -f "$SRC" ]]; then
|
|
37
|
+
echo "Template missing: $SRC" >&2
|
|
38
|
+
echo "Did you build the ros2 workspace? (cd $ROOT/ros2_ws && colcon build)" >&2
|
|
39
|
+
exit 1
|
|
40
|
+
fi
|
|
41
|
+
|
|
42
|
+
if [[ "$PRINT_ONLY" == "true" ]]; then
|
|
43
|
+
cat "$SRC"
|
|
44
|
+
exit 0
|
|
45
|
+
fi
|
|
46
|
+
|
|
47
|
+
mkdir -p "$DEST_DIR"
|
|
48
|
+
|
|
49
|
+
if [[ -f "$DEST" ]]; then
|
|
50
|
+
if [[ "$DO_BACKUP" == "true" ]]; then
|
|
51
|
+
BAK="${DEST}.real.$(date +%Y%m%d-%H%M%S).bak"
|
|
52
|
+
cp -a "$DEST" "$BAK"
|
|
53
|
+
echo "[configure_for_sim] Backed up existing config -> $BAK"
|
|
54
|
+
else
|
|
55
|
+
echo "[configure_for_sim] $DEST already exists. Re-run with --backup to keep a copy." >&2
|
|
56
|
+
echo "[configure_for_sim] Aborting (use --backup to overwrite)." >&2
|
|
57
|
+
exit 1
|
|
58
|
+
fi
|
|
59
|
+
fi
|
|
60
|
+
|
|
61
|
+
cp "$SRC" "$DEST"
|
|
62
|
+
echo "[configure_for_sim] Wrote $DEST"
|
|
63
|
+
echo "[configure_for_sim] Inspect with: agenticros config show"
|
|
64
|
+
echo "[configure_for_sim] Bring up sim with: agenticros up sim-amr"
|