Skip to content

Commit d5f974b

Browse files
authored
Merge pull request #188 from compas-dev/feature/robot
Feature/robot
2 parents b768d60 + 4b85701 commit d5f974b

File tree

2 files changed

+34
-0
lines changed

2 files changed

+34
-0
lines changed

CHANGELOG.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
2222
* Added `list[float]` to accepted types for `Camera.position` and `Camera.target`.
2323
* Added `unit` to `Viewer` and `Config`.
2424
* Added `bounding_box` and `_update_bounding_box` to `BufferObject`.
25+
* Added `robot.py` example.
2526

2627
### Changed
2728

scripts/robot.py

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
from compas_robots import RobotModel
2+
from compas_robots.resources import GithubPackageMeshLoader
3+
from compas_robots.viewer.scene.robotmodelobject import RobotModelObject
4+
from compas_viewer.components import Slider
5+
from compas_viewer import Viewer
6+
7+
viewer = Viewer()
8+
viewer.renderer.rendermode="lighted"
9+
10+
github = GithubPackageMeshLoader("ros-industrial/abb", "abb_irb6600_support", "kinetic-devel")
11+
model = RobotModel.from_urdf_file(github.load_urdf("irb6640.urdf"))
12+
model.load_geometry(github)
13+
14+
configuration = model.zero_configuration()
15+
robot_object: RobotModelObject = viewer.scene.add(model, show_lines=False, configuration=configuration) # type: ignore
16+
17+
viewer.ui.sidedock.show = True
18+
19+
def make_rotate_function(index):
20+
def rotate(slider: Slider, value: int):
21+
config = robot_object.configuration
22+
config.joint_values[index] = value / 360 * 2 * 3.14159
23+
robot_object.update_joints(config)
24+
return rotate
25+
26+
for i, joint in enumerate(robot_object.configuration.joint_names):
27+
rotate_function = make_rotate_function(i)
28+
viewer.ui.sidedock.add(Slider(title=joint, starting_val=0, min_val=-180, max_val=180, step=1, action=rotate_function))
29+
30+
31+
robot_object.update_joints(robot_object.configuration)
32+
33+
viewer.show()

0 commit comments

Comments
 (0)