Comments (14)
Ok, please let me get back to you on Monday.
from talos_robot.
Adjusting the xyz and rpy of the joint should be sufficient to handle this issue, shouldn't it ?
No, because the motor is still moving outside it's operating range, at maybe when going over 90º it might be hitting a mechanical limit and not reaching the desired position and therefore overheating.
What about providing 7 parameters (xyz_offset, rpy_offset and transmission_offset) and let the one who calibrates choose the method that suits its need ?
You need both, because they correct different problems. The transmission_offset corrects the motor range of motion. The other compensates for deviations from the manufacturing process.
For a new robot, you need to calibrate xyz_offset and rpy_offset using a precise (but time consuming) method (like MoCap). At this step, you leave the transmission offset to zero.
Later on, after some usage of the robot, a transmission offset may appear and one could use another simpler method to estimate those offsets (like finding when the bounds are hit on each side of each joint)
Agree 100%
from talos_robot.
Hi @jmirabel,
We were beginning to work on calibrating the 3d position in addition to the joint offset of the arms, but have no ETA yet.
If you submit a proposal, we'll be happy to review it and get it into shape quickly as to not delay your work.
May I ask how are you performing the calibration? Do you have any results yet?
Best regards
from talos_robot.
If you submit a proposal, we'll be happy to review it and get it into shape quickly as to not delay your work.
Before I do anything, I would like to agree with you on the method.
One possibility I have in mind is as follows. At the moment, the URDF chain is something like link -> joint -> link ...
. We could do something like link -> calibration_frame -> empty_link -> joint_calibration -> link ...
where calibration_frame
is a fixed joint containing the pose currently in joint and joint_calibration
is the revolute joint whose 6D position is close to 0. The pose of the joint_calibration
can be parameterized like the current joint offsets.
The discussion might become cumbersome to write. I am open to an oral discussion through any channel.
May I ask how are you performing the calibration? Do you have any results yet?
For the 6D joint pose, we use a motion capture system. We haven't been able to validate the calibration result on the robot yet but it should come soon.
from talos_robot.
Here is a draft of what I meant: jmirabel@569acff
from talos_robot.
If possible we'd like to avoid extra links on the URDF, it could cause unknown effects on lots of parts of the code.
We were thinking something similar to what we have with the joint offsets.
We'd add 6 variables for x,y,z and r,p,y per joint in the existing calibration urdf file. They would replace the current joint offset variable.
In order to apply this variables, we'd add them here: https://github.com/pal-robotics/talos_robot/blob/kinetic-devel/talos_description/urdf/arm/arm.urdf.xacro#L59
So it would become:
<origin xyz="${0.00000 + x_offset} ${0.15750*reflect + y_offset} ${0.23200 + z_offset}"
rpy="${0.0 * deg_to_rad + roll_offset} ${0.0 * deg_to_rad + pitch_offset} ${0.0 * deg_to_rad}"/>
<axis xyz="0 0 1" />
Notice that I didn't add + yaw_offset
. It is because this offset that coincides with the rotation angle of this joint, and it must be added to the transmission like we do already.
So for each joint, you'd apply 5 offsets here, and the one rotation offset that is aligned with the joint rotation axis must be added to the transmissions here
So this bit would become:
<xacro:talos_arm_simple_transmission name="${name}" side="right" number="1" reduction="1.0" offset_value="${arm_right_1_yaw_offset}" />
<xacro:talos_arm_simple_transmission name="${name}" side="right" number="2" reduction="1.0" offset_value="${arm_right_2_roll_offset}" />
<xacro:talos_arm_simple_transmission name="${name}" side="right" number="3" reduction="1.0" offset_value="${arm_right_3_yaw_offset}" />
<xacro:talos_arm_simple_transmission name="${name}" side="right" number="4" reduction="1.0" offset_value="${arm_right_4_pitch_offset}" />
Does it make sense? We would develop this in the next weeks.
from talos_robot.
This would work. Thank you for your time.
from talos_robot.
Notice that I didn't add
+ yaw_offset
. It is because this offset that coincides with the rotation angle of this joint, and it must be added to the transmission like we do already.So for each joint, you'd apply 5 offsets here, and the one rotation offset that is aligned with the joint rotation axis must be added to the transmissions here
After double-thinking about it, this has one slight drawback.
The offset do not have the same meaning depending on the rotation axis. In the calibration file, one will see roll_offset, pitch_offset and yaw_offset. However, the order of application of the offset will not be applied in the same order.
The rotation matrix of a joint will be
- for a joint rotating around X:
Rx(q+roll_offset) * Rz (yaw + yaw_offset) * Ry (pitch + pitch_offset) * Rx (roll)
, - for a joint rotating around Y:
Ry(q+pitch_offset) * Rz (yaw + yaw_offset) * Ry (pitch) * Rx (roll + roll_offset)
,
whereq
is the joint parameter.
This makes the API slightly awkward. Computing the offsets is still possible but requires to play around with Euler angles conventions. This will for sure give a headache to the developer.
Is there a specific reason to keep the calibration of the transmission ?
from talos_robot.
I hadn't thought of that.
The reason for keeping it in the transmission, is that while we don't expect big changes in the roll, pitch and yaw in the physical location of the joint due to assembly, it is expected that the joints might have some offset at the actuator level, some encoder mounting difference or any similar thing. That's why that joint offset was there in the first place.
It's important to differentiate between that external and internal offset. For an external offset we just adjust the x,y,z or r,p,y transform and that's good.
But if the arm is supposed to be moving from 0º to 90º, and it is instead moving from 5º to 95º due to some internal actuator tolerances, we need to correct this 5º offset at the joint level. Otherwise the arm might hit the mechanical limits or cause self collisions.
If we have two separate processes to determine the internal joint offset, and the external mounting offset, then it may make sense to apply all x,y,z and r,p,y at the joint origin transform, and the internal offset at the transmission level.
Please let me know what you think, while we move this internally a bit more.
from talos_robot.
But if the arm is supposed to be moving from 0º to 90º, and it is instead moving from 5º to 95º due to some internal actuator tolerances, we need to correct this 5º offset at the joint level. Otherwise the arm might hit the mechanical limits or cause self collisions.
Adjusting the xyz and rpy of the joint should be sufficient to handle this issue, shouldn't it ?
What about providing 7 parameters (xyz_offset, rpy_offset and transmission_offset) and let the one who calibrates choose the method that suits its need ?
For a new robot, you need to calibrate xyz_offset and rpy_offset using a precise (but time consuming) method (like MoCap). At this step, you leave the transmission offset to zero.
Later on, after some usage of the robot, a transmission offset may appear and one could use another simpler method to estimate those offsets (like finding when the bounds are hit on each side of each joint)
from talos_robot.
Alright, we had one more discussion about this.
The joint offset we can apply at a lower level, at the motor configuration files of each joint.
Therefore on the talos_description_calibration only the XYZ and RPY remains.
These motor calibration files are also accessible to you in case you needed to modify, but ideally after we've calibrated them they should not need to be touched anymore.
from talos_robot.
I needed to move forward. You may take inspiration from 362fcb8.
I did not remove the transmission offsets (I'll keep them to zero) and I did not add offsets to the legs, which we won't calibrate (at least in a first phase).
from talos_robot.
Looks good, sorry we couldn't get on this before next week. It's most going to look very similar to this.
Very nice idea to use one file per arm to avoid having to deal with side
as part of the variable name.
from talos_robot.
We merged your changes with slight modifications: d788118
from talos_robot.
Related Issues (6)
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from talos_robot.