Skip to content

Commit

Permalink
Merge pull request #188 from compas-dev/feature/robot
Browse files Browse the repository at this point in the history
Feature/robot
  • Loading branch information
Licini authored Jul 18, 2024
2 parents b768d60 + 4b85701 commit d5f974b
Show file tree
Hide file tree
Showing 2 changed files with 34 additions and 0 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
* Added `list[float]` to accepted types for `Camera.position` and `Camera.target`.
* Added `unit` to `Viewer` and `Config`.
* Added `bounding_box` and `_update_bounding_box` to `BufferObject`.
* Added `robot.py` example.

### Changed

Expand Down
33 changes: 33 additions & 0 deletions scripts/robot.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
from compas_robots import RobotModel
from compas_robots.resources import GithubPackageMeshLoader
from compas_robots.viewer.scene.robotmodelobject import RobotModelObject
from compas_viewer.components import Slider
from compas_viewer import Viewer

viewer = Viewer()
viewer.renderer.rendermode="lighted"

github = GithubPackageMeshLoader("ros-industrial/abb", "abb_irb6600_support", "kinetic-devel")
model = RobotModel.from_urdf_file(github.load_urdf("irb6640.urdf"))
model.load_geometry(github)

configuration = model.zero_configuration()
robot_object: RobotModelObject = viewer.scene.add(model, show_lines=False, configuration=configuration) # type: ignore

viewer.ui.sidedock.show = True

def make_rotate_function(index):
def rotate(slider: Slider, value: int):
config = robot_object.configuration
config.joint_values[index] = value / 360 * 2 * 3.14159
robot_object.update_joints(config)
return rotate

for i, joint in enumerate(robot_object.configuration.joint_names):
rotate_function = make_rotate_function(i)
viewer.ui.sidedock.add(Slider(title=joint, starting_val=0, min_val=-180, max_val=180, step=1, action=rotate_function))


robot_object.update_joints(robot_object.configuration)

viewer.show()

0 comments on commit d5f974b

Please sign in to comment.