Skip to content

Commit 1775c0f

Browse files
Fix resource_manager for simulation (#304)
* Fix resource_manager for simulation * fix start points * update readme * update readme --------- Co-authored-by: Marija Golubovic <marijagolubovic16@gmail.com>
1 parent 46ff4f8 commit 1775c0f

File tree

6 files changed

+112
-97
lines changed

6 files changed

+112
-97
lines changed

README.md

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ git clone git@github.com:memristor/mep3.git src/mep3
1818

1919
# Install dependencies
2020
sudo apt install python3-vcstool
21-
vcs import src < src/mep3/mep3.repos
21+
# vcs import src < src/mep3/mep3.repos
2222
rosdep update
2323
rosdep install --from-paths src --ignore-src -r
2424

@@ -29,6 +29,7 @@ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
2929
source install/local_setup.bash
3030
```
3131

32+
⚠️ **Recommended:**
3233
Please check alternative installation methods [here](./docker).
3334

3435
## Bringup
@@ -64,6 +65,9 @@ Important parameters are:
6465
### Demo
6566

6667
#### Teleoperation
68+
>[!NOTE]
69+
Run simulation without behavior tree
70+
6771
```sh
6872
ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args -r cmd_vel:=big/cmd_vel
6973
```

docker/Dockerfile.base

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -83,11 +83,16 @@ RUN curl -L -o /opt/Groot2.AppImge \
8383

8484
RUN python3 -m pip install scipy transforms3d
8585

86-
#HOTFIX: https://github.com/ros-controls/ros2_controllers/issues/482
86+
# HOTFIX: https://github.com/ros-controls/ros2_controllers/issues/482
8787
RUN wget -O /tmp/diff_drive_controller.deb http://snapshots.ros.org/humble/2022-11-23/ubuntu/pool/main/r/ros-humble-diff-drive-controller/ros-humble-diff-drive-controller_2.12.0-1jammy.20221108.202153_amd64.deb && \
8888
apt install -y --allow-downgrades /tmp/diff_drive_controller.deb && \
8989
rm -f /tmp/diff_drive_controller.deb
9090

91+
# HOTFIX: https://github.com/ros-controls/ros2_control/pull/1960
92+
RUN wget -O /tmp/hotfix.deb http://snapshots.ros.org/humble/2024-08-28/ubuntu/pool/main/r/ros-humble-hardware-interface/ros-humble-hardware-interface_2.43.0-1jammy.20240823.145349_amd64.deb && \
93+
apt install -y --allow-downgrades /tmp/hotfix.deb && \
94+
rm -f /tmp/hotfix.deb
95+
9196
# User config
9297
COPY ./config/bashrc /tmp/bashrc
9398
COPY ./config/fish/. /memristor/.config/fish/

mep3_bringup/launch/simulation_launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
def generate_launch_description():
1616
use_behavior_tree = LaunchConfiguration('bt', default=True)
17-
big_strategy = LaunchConfiguration('big_strategy', default='test_mechanism')
17+
big_strategy = LaunchConfiguration('big_strategy', default='blue_new_a')
1818
small_strategy = LaunchConfiguration('small_strategy', default='wait_everytime')
1919
color = LaunchConfiguration('color', default='blue')
2020
namespace = LaunchConfiguration('namespace', default='big')

mep3_simulation/resource/big_description.urdf

Lines changed: 94 additions & 87 deletions
Original file line numberDiff line numberDiff line change
@@ -43,109 +43,116 @@
4343
<command_interface name="output" />
4444
</gpio>
4545
<joint name="m1">
46-
<command_interface name="position"/>
47-
<command_interface name="velocity"/>
48-
<state_interface name="position"/>
49-
<state_interface name="velocity"/>
50-
<state_interface name="effort"/>
46+
<command_interface name="position" />
47+
<command_interface name="velocity" />
48+
<state_interface name="position" />
49+
<state_interface name="velocity" />
50+
<state_interface name="effort" />
5151
</joint>
5252
<joint name="m2">
53-
<command_interface name="position"/>
54-
<command_interface name="velocity"/>
55-
<state_interface name="position"/>
56-
<state_interface name="velocity"/>
57-
<state_interface name="effort"/>
53+
<command_interface name="position" />
54+
<command_interface name="velocity" />
55+
<state_interface name="position" />
56+
<state_interface name="velocity" />
57+
<state_interface name="effort" />
5858
</joint>
5959
<joint name="m3">
60-
<command_interface name="position"/>
61-
<command_interface name="velocity"/>
62-
<state_interface name="position"/>
63-
<state_interface name="velocity"/>
64-
<state_interface name="effort"/>
60+
<command_interface name="position" />
61+
<command_interface name="velocity" />
62+
<state_interface name="position" />
63+
<state_interface name="velocity" />
64+
<state_interface name="effort" />
6565
</joint>
6666
<joint name="m4">
67-
<command_interface name="position"/>
68-
<command_interface name="velocity"/>
69-
<state_interface name="position"/>
70-
<state_interface name="velocity"/>
71-
<state_interface name="effort"/>
67+
<command_interface name="position" />
68+
<command_interface name="velocity" />
69+
<state_interface name="position" />
70+
<state_interface name="velocity" />
71+
<state_interface name="effort" />
7272
</joint>
7373
<joint name="m5">
74-
<command_interface name="position"/>
75-
<command_interface name="velocity"/>
76-
<state_interface name="position"/>
77-
<state_interface name="velocity"/>
78-
<state_interface name="effort"/>
74+
<command_interface name="position" />
75+
<command_interface name="velocity" />
76+
<state_interface name="position" />
77+
<state_interface name="velocity" />
78+
<state_interface name="effort" />
7979
</joint>
8080
<joint name="m6">
81-
<command_interface name="position"/>
82-
<command_interface name="velocity"/>
83-
<state_interface name="position"/>
84-
<state_interface name="velocity"/>
85-
<state_interface name="effort"/>
81+
<command_interface name="position" />
82+
<command_interface name="velocity" />
83+
<state_interface name="position" />
84+
<state_interface name="velocity" />
85+
<state_interface name="effort" />
8686
</joint>
8787
<joint name="m7">
88-
<command_interface name="position"/>
89-
<command_interface name="velocity"/>
90-
<state_interface name="position"/>
91-
<state_interface name="velocity"/>
92-
<state_interface name="effort"/>
88+
<command_interface name="position" />
89+
<command_interface name="velocity" />
90+
<state_interface name="position" />
91+
<state_interface name="velocity" />
92+
<state_interface name="effort" />
9393
</joint>
9494
<joint name="m8">
95-
<command_interface name="position"/>
96-
<command_interface name="velocity"/>
97-
<state_interface name="position"/>
98-
<state_interface name="velocity"/>
99-
<state_interface name="effort"/>
95+
<command_interface name="position" />
96+
<command_interface name="velocity" />
97+
<state_interface name="position" />
98+
<state_interface name="velocity" />
99+
<state_interface name="effort" />
100100
</joint>
101101
<joint name="m9">
102-
<command_interface name="position"/>
103-
<command_interface name="velocity"/>
104-
<state_interface name="position"/>
105-
<state_interface name="velocity"/>
106-
<state_interface name="effort"/>
102+
<command_interface name="position" />
103+
<command_interface name="velocity" />
104+
<state_interface name="position" />
105+
<state_interface name="velocity" />
106+
<state_interface name="effort" />
107+
</joint>
108+
<joint name="m10">
109+
<command_interface name="position" />
110+
<command_interface name="velocity" />
111+
<state_interface name="position" />
112+
<state_interface name="velocity" />
113+
<state_interface name="effort" />
107114
</joint>
108115
<joint name="m10">
109-
<command_interface name="position"/>
110-
<command_interface name="velocity"/>
111-
<state_interface name="position"/>
112-
<state_interface name="velocity"/>
113-
<state_interface name="effort"/>
114-
</joint>
115-
<joint name="m10">
116-
<command_interface name="position"/>
117-
<command_interface name="velocity"/>
118-
<state_interface name="position"/>
119-
<state_interface name="velocity"/>
120-
<state_interface name="effort"/>
121-
</joint>
122-
<joint name="m11">
123-
<command_interface name="position"/>
124-
<command_interface name="velocity"/>
125-
<state_interface name="position"/>
126-
<state_interface name="velocity"/>
127-
<state_interface name="effort"/>
128-
</joint>
129-
<joint name="m12">
130-
<command_interface name="position"/>
131-
<command_interface name="velocity"/>
132-
<state_interface name="position"/>
133-
<state_interface name="velocity"/>
134-
<state_interface name="effort"/>
135-
</joint>
136-
<joint name="m13">
137-
<command_interface name="position"/>
138-
<command_interface name="velocity"/>
139-
<state_interface name="position"/>
140-
<state_interface name="velocity"/>
141-
<state_interface name="effort"/>
142-
</joint>
143-
<joint name="m14">
144-
<command_interface name="position"/>
145-
<command_interface name="velocity"/>
146-
<state_interface name="position"/>
147-
<state_interface name="velocity"/>
148-
<state_interface name="effort"/>
149-
</joint>
116+
<command_interface name="position" />
117+
<command_interface name="velocity" />
118+
<state_interface name="position" />
119+
<state_interface name="velocity" />
120+
<state_interface name="effort" />
121+
</joint>
122+
<joint name="m11">
123+
<command_interface name="position" />
124+
<command_interface name="velocity" />
125+
<state_interface name="position" />
126+
<state_interface name="velocity" />
127+
<state_interface name="effort" />
128+
</joint>
129+
<joint name="m12">
130+
<command_interface name="position" />
131+
<command_interface name="velocity" />
132+
<state_interface name="position" />
133+
<state_interface name="velocity" />
134+
<state_interface name="effort" />
135+
</joint>
136+
<joint name="m13">
137+
<command_interface name="position" />
138+
<command_interface name="velocity" />
139+
<state_interface name="position" />
140+
<state_interface name="velocity" />
141+
<state_interface name="effort" />
142+
</joint>
143+
<joint name="m14">
144+
<command_interface name="position" />
145+
<command_interface name="velocity" />
146+
<state_interface name="position" />
147+
<state_interface name="velocity" />
148+
<state_interface name="effort" />
149+
</joint>
150+
<joint name="m15">
151+
<command_interface name="position" />
152+
<command_interface name="velocity" />
153+
<state_interface name="position" />
154+
<state_interface name="velocity" />
155+
<state_interface name="effort" />
156+
</joint>
150157
</ros2_control>
151-
</robot>
158+
</robot>

mep3_simulation/src/mep3_webots_hardware_interface.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -94,7 +94,7 @@ namespace mep3_simulation
9494

9595
for (FakeJoint &fake_joint : fake_joints_) {
9696
fake_joint.write_counter++;
97-
fake_joint.position += sign(fake_joint.command_position - fake_joint.position) * 0.005;
97+
fake_joint.position = fake_joint.command_position;
9898
fake_joint.velocity = fake_joint.command_velocity;
9999
fake_joint.effort = fake_joint.write_counter % 80;
100100
}

mep3_simulation/webots_data/controllers/judge/judge.py

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77

88
INITIAL_POSE_MATRIX = [
99
# ('big', 'blue', [0.03, -1.15, pi/2]), # centralno polje
10-
('big', 'blue', [0.815, -1.33, -pi/2]), # polje kod panela
10+
('big', 'blue', [0.815, -1.33, pi/2]), # polje kod panela
1111
('big', 'yellow', [0.80, 1.33, -pi/2]), # polje kod panela
1212

1313
('big', 'blue_a', [0.045, 1.31, -pi/2]), # centralno polje
@@ -16,11 +16,10 @@
1616
('big', 'blue_b', [0.81, -1.34, -pi/2]), # unazad kod panela
1717
('big', 'yellow_b', [0.045, -1.31, pi/2]), # unazad kod panela
1818

19-
# ('small', 'blue', [-0.72, -1.16, pi/2]),
20-
21-
# ('small', 'green', [-0.72, 1.16, pi/2]),
22-
# ('big', 'green', [-0.72, -1.16, pi/2])
19+
('small', 'blue', [-0.72, -1.16, pi/2]),
2320

21+
('small', 'yellow', [-0.72, 1.16, pi/2]),
22+
('big', 'yellow', [-0.72, -1.16, pi/2])
2423
]
2524

2625

@@ -65,7 +64,7 @@ def main():
6564
robot_small.set_position(x=pose_small[0], y=pose_small[1], theta=pose_small[2])
6665

6766
robot_opponent_big.set_position(x=pose_big[0], y=-pose_big[1], theta=pose_big[2])
68-
robot_opponent_small.set_position(x=-pose_small[0], y=pose_small[1], theta=pose_small[2])
67+
robot_opponent_small.set_position(x= pose_small[0], y=-pose_small[1], theta=pose_small[2])
6968

7069
supervisor.step(timestep)
7170

0 commit comments

Comments
 (0)