This is a copy of issue: Robot from docker-ros with wrong position · Issue #166 · compas-dev/compas_view2 · GitHub
Robot from docker-ros with the wrong position
I am running a code very similar to v120_robot.py with the only change that the robot is not from GitHub but docker-ros:
with RosClient() as ros:
robot = ros.load_robot(load_geometry=True)
model = robot.model
While the robot is positional wrong:
I tried different docker files, but the results remain incorrect.
also, the below code is also not working with NotImplementedError: Mesh type not supported: dae
from compas_view2.app import App
from compas.robots import LocalPackageMeshLoader
from compas.robots import RobotModel
import compas_fab
urdf = compas_fab.get('universal_robot/ur_description/urdf/ur10.urdf')
model = RobotModel.from_urdf_file(urdf)
# Also load geometry
loader = LocalPackageMeshLoader(compas_fab.get('universal_robot'), 'ur_description')
model.load_geometry(loader)
viewer = App()
robot_object = viewer.add(model)
viewer.run()
Hi Zac,
Will take a deeper look later, but if you do not load geometry, does the joints and axis looks correct? Should be something like this:
not sure, i tunned the joint values into all zero and it looks not correct
from compas_view2.app import App
from compas.geometry import Box
from compas.geometry import Frame
from compas_fab.backends import RosClient
with RosClient() as ros:
robot = ros.load_robot(load_geometry=False)
model = robot.model
viewer = App(viewmode="lighted", enable_sceneform=True, enable_sidebar=True, width=2000, height=1000)
robotObj = viewer.add(model)
end_effector_link_obj = robotObj.link_objs[model.get_end_effector_link_name()]
end_effector_link_obj.add(Box(Frame([0, 0, 0.25], [1, 0, 0], [0, 1, 0]), 0.2, 0.2, 0.5), name="end_effector_dummy_box")
for joint_name in model.get_configurable_joint_names():
robotObj.rotate_joint(joint_name, 0)
viewer.show()
Hey Zac, I’ve able to find the reason. It is because the visual geometry of robots some times have different origin than the joint itself. I will make a new release to fix this in the Robot object. But for now you can use this custom script to load ROS robots correctly.
from compas_view2.app import App
from compas_view2.collections import Collection
import itertools
from compas.geometry import Transformation
from compas.geometry import Rotation
from compas.robots import Geometry
from math import radians
from compas_fab.backends import RosClient
with RosClient() as ros:
robot = ros.load_robot(load_geometry=True)
print(robot.model)
model = robot.model
viewer = App(viewmode="lighted", enable_sceneform=True, enable_propertyform=True, enable_sidebar=True, width=2000, height=1000)
def create(link, parent=None, parent_joint=None):
obj = None
meshes = []
for item in itertools.chain(link.visual):
meshes.extend(Geometry._get_item_meshes(item))
if item.origin:
for mesh in meshes:
mesh.transform(Transformation.from_frame(item.origin))
obj = parent.add(Collection(meshes), name=link.name, show_lines=False)
if parent_joint:
obj.matrix = Transformation.from_frame(parent_joint.origin).matrix
@viewer.slider(title=parent_joint.name, minval=-180 , maxval=180)
def rotate(angle):
T = Transformation.from_frame(parent_joint.origin)
R = Rotation.from_axis_and_angle(parent_joint.axis.vector, radians(angle))
obj.matrix = (T * R).matrix
viewer.view.update()
for joint in link.joints:
create(joint.child_link, parent = obj, parent_joint=joint)
create(model.root, viewer)
viewer.show()
1 Like
Super! Thank you very much for the solution!