-
Notifications
You must be signed in to change notification settings - Fork 38
Robot
A Robot behaves like a FreeCAD group and should contain only Link and Joint objects.
A * Robot* has a Placement property that is used to place the robot in the scene.
The Label of the Robot is used as the name of the robot in the URDF file (attribute name
of the robot
tag).
The Output Path property of the Robot is used when you use the Export URDF command. It is the path where the robot description package will be created. If you are not familiar to the structure of a robot description package, you can use the Export URDF command to create a package and then inspect it or consult this page. The recommended structure of the ROS package is the following:
myrob_description/
├── CMakeLists.txt
├── package.xml
├── urdf/
│ └── myrob.urdf
└── meshes/
└── myrob.dae
When the Robot contains at least one Joint that is not fixed, a property is added to the Robot to give a position to all robot joints. For example, if the robot has a revolute joint q0
, the position of this joint can be changed via the q0_deg
property.
The properties in the Material section determine the default material density used for the computation of the inertial properties of the links belonging to the robot.
Change the Joint Axis Length property of all its joints.
Toggle the visibility of the real, visual, and collision elements of the robot's links.
Toggle the Show Axes property of all its joints.
The action Load trajectory from YAML… is accessible from the context-menu of a Robot object.
It allows to load a trajectory from a multi-document YAML file containing one moveit_msgs/msg/DisplayTrajectory message per document.
The current use case is to get trajectories with ros2 topic echo /display_planned_path
(for example by redirecting the console output with ros2 topic echo /display_planned_path > /tmp/display_planned_path.yaml
) and load them with the context-menu of a trajectory in FreeCAD's document tree.
One Trajectory is created for each document in the YAML file.
from freecad.cross.robot_proxy import make_robot
doc = fc.activeDocument()
robot = make_robot('anton', doc)
# Optionaly.
robot.ViewObject.JointAxisLength = 50.0
robot.ViewObject.ShowJointAxes = True
robot.ViewObject.ShowReal = False
robot.ViewObject.ShowVisual = True
robot.ViewObject.ShowCollision = False
robot.OutputPath = '/home/user/ros2_ws/src'