rl
rl copied to clipboard
using URDF robot description
hi there, please let me know how I can use a URDF file description of robot for generating kinematic model , I have look down your rl::mdl:: urdffactory but the format is not clear how to create and load the urdf file instead of xml format , if you can please write down the command syntax. for using say robotmodel.urdf file stored at rl/share/mdl folder where other models xml files are stored. code syntax required for windows c++ visual studio 2017 thanks for your help .!
code syntax required for windows c++ visual studio 2017 rl::mdl::UrdfFactory urdf_factory; rl::mdl::Kinematic* kinematics = dynamic_castrl::mdl::Kinematic*(urdf_factory.create("C:\Program Files\RoboticsLibrary\0.7.0\MSVC\14.1\x64\share\rl0.7.0\examples\rlmdl\robot_model.urdf"));
The Factory::create function on the master branch now returns a std::shared_ptr<Model> instead of the Model* in the 0.7 branch. The dynamic_cast therefore has to be replaced with a std::dynamic_pointer_cast. You can also have a look at rlInversePositionDemo.cpp for an additional example.
rl::mdl::UrdfFactory urdf_factory;
std::shared_ptr<rl::mdl::Kinematic> kinematics = std::dynamic_pointer_cast<rl::mdl::Kinematic>(
urdf_factory.create("C:\\Program Files\\RoboticsLibrary\\0.7.0\\MSVC\\14.1\\x64\\share\\rl-0.7.0\\examples\\rlmdl\\robot_model.urdf")
);
hi , I have used the code as mentioned but it only works with the master branch and source installation of current RL lib. but I prefer to use rl-0.7 branch as it comes with pre-built bin for 3rd party libraries as I need to use other functionality like boost , eigen and qt run time etc ,it was installed in win bin rl-0.7 branch.
what is the way to incorporate current master branch with Win-bin installation rl-0.7 ? thanks.
For the rl-0.7 branch the code should look like this (with shared pointer)
rl::mdl::UrdfFactory urdf_factory;
std::shared_ptr<rl::mdl::Kinematic> kinematics(
dynamic_cast<rl::mdl::Kinematic*>(
urdf_factory.create("C:\\Program Files\\RoboticsLibrary\\0.7.0\\MSVC\\14.1\\x64\\share\\rl-0.7.0\\examples\\rlmdl\\robot_model.urdf")
)
);
or this (without shared pointer)
rl::mdl::UrdfFactory urdf_factory;
rl::mdl::Kinematic* kinematics = dynamic_cast<rl::mdl::Kinematic*>(
urdf_factory.create("C:\\Program Files\\RoboticsLibrary\\0.7.0\\MSVC\\14.1\\x64\\share\\rl-0.7.0\\examples\\rlmdl\\robot_model.urdf")
);
Getting the third-party libraries on Windows currently is more work than on Linux or macOS. Building them yourself however should be easier with the CMake ExternalProject definitions in the 3rdparty subfolder. Did you have a look at our tutorial on this? Microsoft's vcpkg may be an alternative in the future, but at the moment the related Coin and SoQt PR is not merged yet and you still have to compile everything locally.
I know we should do another release with an updated installer at some point, but I'm kind of hoping to get the GitHub Actions for Windows running first in order to automate this.
The third-party binaries in the 0.7 installer should still be compatible with the current master branch. Let me know if you need any specific binaries, I've built all of them locally with VS2019 x64.
Hello! I have a URDF file from Kinova that I wanted to use, it can be found here, but it doesnt seem to work. If I try to get info from model, like model->getDof() or anything else, it seems like it's not initialized.
int main(int argc, char **argv) {
try
{
rl::mdl::UrdfFactory factory;
std::shared_ptr<rl::mdl::Model> model;
model.reset(factory.create("E:\\Home\\User\\Documents\\KORTEX\\master\\kortex-master\\api_cpp\\examples\\GEN3_URDF_V12.urdf"));
std::cerr << "Model created, DoF: " << model.get()->getDof() << std::endl;
std::shared_ptr<rl::mdl::Kinematic> kinematic = dynamic_pointer_cast<rl::mdl::Kinematic>(model);
rl::math::Vector q(7);
std::cerr << "Vec Loaded " << std::endl;
q << 10, 10, -20, 30, 50, -10, 1;
std::cerr << "Vec Set" << q.transpose() << std::endl;
q *= rl::math::DEG2RAD;
std::cerr << "Vec in RAD" << q.transpose() << std::endl;
kinematic->setPosition(q);
std::cerr << "Pos Set" << std::endl;
kinematic->forwardPosition();
std::cerr << "Fwd done" << std::endl;
rl::math::Transform t = kinematic->getOperationalPosition(0);
std::cerr << "Transform" << std::endl;
rl::math::Vector3 position = t.translation();
std::cerr << "Translate" << std::endl;
rl::math::Vector3 orientation = t.rotation().eulerAngles(2, 1, 0).reverse();
std::cout << "Joint configuration in degrees: " << q.transpose() * rl::math::RAD2DEG << std::endl;
std::cout << "End-effector position: [m] " << position.transpose() << " orientation [deg] " << orientation.transpose() * rl::math::RAD2DEG << std::endl;
}
catch(const std::exception& e)
{
std::cerr << e.what() << '\n';
}
return 0;
}
gives me this output:
GEN3_URDF_V12
link: 0
cog: -0.000648 -0.000166 0.084487
inertia: 0.004622 0.004495 0.002079 9e-06 6e-05 9e-06
mass: 1.697
name: base_link
link: 1
cog: -2.3e-05 -0.010364 -0.07336
inertia: 0.00457 0.004831 0.001409 0.000448 2e-06 1e-06
mass: 1.3773
name: Shoulder_Link
link: 2
cog: -4.4e-05 -0.09958 -0.013278
inertia: 0.011088 0.001072 0.011255 -0.000691 0 5e-06
mass: 1.1636
name: HalfArm1_Link
link: 3
cog: -4.4e-05 -0.006641 -0.117892
inertia: 0.010932 0.011127 0.001043 0.000606 -7e-06 0
mass: 1.1636
name: HalfArm2_Link
link: 4
cog: -1.8e-05 -0.075478 -0.015006
inertia: 0.008147 0.000631 0.008316 -0.0005 0 -1e-06
mass: 0.9302
name: ForeArm_Link
link: 5
cog: 1e-06 -0.009432 -0.063883
inertia: 0.001596 0.001607 0.000399 0.000256 0 0
mass: 0.6781
name: SphericalWrist1_Link
link: 6
cog: 1e-06 -0.045483 -0.00965
inertia: 0.001641 0.00041 0.001641 -0.000278 0 0
mass: 0.6781
name: SphericalWrist2_Link
link: 7
cog: -0.000281 -0.011402 -0.029798
inertia: 0.000587 0.000369 0.000609 0.000118 3e-06 3e-06
mass: 0.5006
name: Bracelet_Link
link: 8
name: EndEffector_Link
joint: 0
parent: base_link
child: Shoulder_Link
origin.translation: 0 0 0.15643
origin.rotation: -180 -0 0
type: continuous
joint: 1
parent: Shoulder_Link
child: HalfArm1_Link
origin.translation: 0 0.005375 -0.12838
origin.rotation: 90.0002 -0 0
type: revolute
max: 138.083
min: -138.083
speed: 50.002
axis: 0 0 1
name: Actuator2
joint: 2
parent: HalfArm1_Link
child: HalfArm2_Link
origin.translation: 0 -0.21038 -0.006375
origin.rotation: -90.0002 -0 0
type: continuous
joint: 3
parent: HalfArm2_Link
child: ForeArm_Link
origin.translation: 0 0.006375 -0.21038
origin.rotation: 90.0002 -0 0
type: revolute
max: 152.407
min: -152.407
speed: 50.002
axis: 0 0 1
name: Actuator4
joint: 4
parent: ForeArm_Link
child: SphericalWrist1_Link
origin.translation: 0 -0.20843 -0.006375
origin.rotation: -90.0002 -0 0
type: continuous
joint: 5
parent: SphericalWrist1_Link
child: SphericalWrist2_Link
origin.translation: 0 0.00017505 -0.10593
origin.rotation: -89.9998 180 180
type: revolute
max: 127.77
min: -127.77
speed: 50.002
axis: 0 0 1
name: Actuator6
joint: 6
parent: SphericalWrist2_Link
child: Bracelet_Link
origin.translation: 0 -0.10593 -0.00017505
origin.rotation: -90.0002 -0 0
type: continuous
joint: 7
parent: Bracelet_Link
child: EndEffector_Link
origin.translation: 0 0 -0.061525
origin.rotation: 180 -0 0
type: fixed
name: EndEffector
root: base_link
Model created, DoF: 0
Vec Loaded
Vec Set 10 10 -20 30 50 -10 1
Vec in RAD 0.174533 0.174533 -0.349066 0.523599 0.872665 -0.174533 0.0174533
Pos Set
Fwd done
Transform
Translate
Joint configuration in degrees: 10 10 -20 30 50 -10 1
End-effector position: [m] 0 0 0 orientation [deg] 0 -0 0
Meanwhile if I switch to XmlFactory and use one of the XMLs provided in RL, it works and gives me this:
Model created, DoF: 6
Vec Loaded
Vec Set 10 10 -20 30 50 -10 1
Vec in RAD 0.174533 0.174533 -0.349066 0.523599 0.872665 -0.174533 0.0174533
Pos Set
Fwd done
Transform
Translate
Joint configuration in degrees: 10 10 -20 30 50 -10 1
End-effector position: [m] 0.321872 0.20389 1.03928 orientation [deg] -14.9453 39.2476 22.3873
Considering that UrdfFactory prints out all the data that it gets, but the model seem to be uninitialized, I would assume the print out is supposed to give some information about that something is missing, but what? I've also tried to use regular pointers instead of the std::shared_ptr and all sorts of other ways, but end up with the same result.
EDIT: FYI, Used the windows installer, so 0.7.0
EDIT: Noticed I got inverted signs on X and Y compared to the real robot, so had to rotate the <fixed id="fixed_base"> 180 deg on Z .
I solved it by making an XML based on the data in the URDF and the documentations from Kinova (User Guide), so if ya wanna add it to your examples:
GEN3_XML_V12.xml
Tried to add this as a file, but GitHub only accepted TXT etc..
<?xml version="1.0" encoding="UTF-8"?>
<rlmdl xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="rlmdl.xsd">
<model>
<manufacturer>Kinova</manufacturer>
<name>Gen3 7-dof</name>
<world id="world">
<rotation>
<x>0</x>
<y>0</y>
<z>0</z>
</rotation>
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<g>
<x>0</x>
<y>0</y>
<z>9.81</z>
</g>
</world>
<frame id="frame_base"/>
<body id="base_link">
<ignore idref="Shoulder_Link"/>
<cm>
<x>0.000648</x>
<y>-0.000166</y>
<z>0.084487</z>
</cm>
<i>
<xx>0.004622</xx>
<xy>0.000009</xy>
<xz>0.00006</xz>
<yy>0.004495</yy>
<yz>0.000009</yz>
<zz>0.002079</zz>
</i>
<m>1.697</m>
</body>
<frame id="frame0"/>
<frame id="frame1"/>
<body id="Shoulder_Link">
<ignore idref="base_link"/>
<ignore idref="HalfArm1_Link"/>
<cm>
<x>0.000023</x>
<y>-0.010364</y>
<z>-0.07336</z>
</cm>
<i>
<xx>0.00457</xx>
<xy>0.000001</xy>
<xz>0.000002</xz>
<yy>0.004831</yy>
<yz>0.000448</yz>
<zz>0.001409</zz>
</i>
<m>1.3773</m>
</body>
<frame id="frame2"/>
<frame id="frame3"/>
<body id="HalfArm1_Link">
<ignore idref="Shoulder_Link"/>
<ignore idref="HalfArm2_Link"/>
<cm>
<x>0.000044</x>
<y>-0.09958</y>
<z>-0.013278</z>
</cm>
<i>
<xx>0.011088</xx>
<xy>0.000005</xy>
<xz>0</xz>
<yy>0.001072</yy>
<yz>-0.000691</yz>
<zz>0.011255</zz>
</i>
<m>1.1636</m>
</body>
<frame id="frame4"/>
<frame id="frame5"/>
<body id="HalfArm2_Link">
<ignore idref="HalfArm1_Link"/>
<ignore idref="ForeArm_Link"/>
<cm>
<x>0.000044</x>
<y>-0.006641</y>
<z>-0.117892</z>
</cm>
<i>
<xx>0.010932</xx>
<xy>0</xy>
<xz>-0.000007</xz>
<yy>0.011127</yy>
<yz>0.000606</yz>
<zz>0.001043</zz>
</i>
<m>1.1636</m>
</body>
<frame id="frame6"/>
<frame id="frame7"/>
<body id="ForeArm_Link">
<ignore idref="HalfArm2_Link"/>
<ignore idref="SphericalWrist1_Link"/>
<cm>
<x>0.000018</x>
<y>-0.075478</y>
<z>-0.015006</z>
</cm>
<i>
<xx>0.008147</xx>
<xy>-0.000001</xy>
<xz>0</xz>
<yy>0.000631</yy>
<yz>-0.0005</yz>
<zz>0.008316</zz>
</i>
<m>0.9302</m>
</body>
<frame id="frame8"/>
<frame id="frame9"/>
<body id="SphericalWrist1_Link">
<ignore idref="ForeArm_Link"/>
<ignore idref="SphericalWrist2_Link"/>
<cm>
<x>0.000001</x>
<y>-0.009432</y>
<z>-0.063883</z>
</cm>
<i>
<xx>0.001596</xx>
<xy>0</xy>
<xz>0</xz>
<yy>0.001607</yy>
<yz>0.000256</yz>
<zz>0.000399</zz>
</i>
<m>0.6781</m>
</body>
<frame id="frame10"/>
<frame id="frame11"/>
<body id="SphericalWrist2_Link">
<ignore idref="SphericalWrist1_Link"/>
<ignore idref="Bracelet_Link"/>
<cm>
<x>0.000001</x>
<y>-0.045483</y>
<z>-0.00965</z>
</cm>
<i>
<xx>0.001641</xx>
<xy>0</xy>
<xz>0</xz>
<yy>0.00041</yy>
<yz>-0.000278</yz>
<zz>0.001641</zz>
</i>
<m>0.6781</m>
</body>
<frame id="frame12"/>
<frame id="frame13"/>
<body id="Bracelet_Link">
<ignore idref="SphericalWrist2_Link"/>
<cm>
<x>0.000281</x>
<y>-0.011402</y>
<z>-0.029798</z>
</cm>
<i>
<xx>0.000587</xx>
<xy>0.000003</xy>
<xz>0.000003</xz>
<yy>0.000369</yy>
<yz>0.000118</yz>
<zz>0.000609</zz>
</i>
<m>0.5006</m>
</body>
<!-- **********ADD ABOVE HERE********** -->
<!-- Fixing orientation to world? -->
<fixed id="fixed_world">
<frame>
<a idref="world"/>
<b idref="base_link"/>
</frame>
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>180</z>
</rotation>
</fixed>
<!-- Fixed not needed before as DH params world -> base d and theta == 0 -->
<fixed id="fixed_base">
<frame>
<a idref="base_link"/>
<b idref="frame_base"/>
</frame>
<!-- DH params d (transl z) and theta (rot z) for next revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0.2848</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<revolute id="Actuator1"> <!-- type="continuous"> -->
<frame>
<a idref="frame_base"/>
<b idref="frame0"/>
</frame>
<max>9999</max>
<min>-9999</min>
<speed>50</speed>
<axis>
<x>0</x>
<y>0</y>
<z>1</z>
</axis>
</revolute>
<fixed id="fixed1">
<frame>
<a idref="frame0"/>
<b idref="Shoulder_Link"/>
</frame>
<!-- DH params a (transl x) and alpha (rot x) for previous revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>90</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<!-- <origin xyz="0 0 0.15643" rpy="3.1416 2.7629E-18 -4.9305E-36"/> -->
<fixed id="fixed2">
<frame>
<a idref="Shoulder_Link"/>
<b idref="frame1"/>
</frame>
<!-- DH params d (transl z) and theta (rot z) for next revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>-0.0118</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<revolute id="Actuator2"> <!-- type="revolute"> -->
<frame>
<a idref="frame1"/>
<b idref="frame2"/>
</frame>
<max>138</max>
<min>-138</min>
<speed>50</speed>
<axis>
<x>0</x>
<y>0</y>
<z>1</z>
</axis>
</revolute>
<!-- <origin xyz="0 0.005375 -0.12838" rpy="1.5708 2.1343E-17 -1.1102E-16"/> -->
<fixed id="fixed3">
<frame>
<a idref="frame2"/>
<b idref="HalfArm1_Link"/>
</frame>
<!-- DH params a (transl x) and alpha (rot x) for previous revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>90</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<fixed id="fixed4">
<frame>
<a idref="HalfArm1_Link"/>
<b idref="frame3"/>
</frame>
<!-- DH params d (transl z) and theta (rot z) for next revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>-0.4208</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>180</z>
</rotation>
</fixed>
<revolute id="Actuator3"> <!-- type="continuous"> -->
<frame>
<a idref="frame3"/>
<b idref="frame4"/>
</frame>
<max>9999</max>
<min>-9999</min>
<speed>50</speed>
<axis>
<x>0</x>
<y>0</y>
<z>1</z>
</axis>
</revolute>
<!-- <origin xyz="0 -0.21038 -0.006375" rpy="-1.5708 1.2326E-32 -2.9122E-16"/> -->
<fixed id="fixed5">
<frame>
<a idref="frame4"/>
<b idref="HalfArm2_Link"/>
</frame>
<!-- DH params a (transl x) and alpha (rot x) for previous revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>90</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<fixed id="fixed6">
<frame>
<a idref="HalfArm2_Link"/>
<b idref="frame5"/>
</frame>
<!-- DH params d (transl z) and theta (rot z) for next revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>-0.0128</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>180</z>
</rotation>
</fixed>
<revolute id="Actuator4"> <!-- type="revolute"> -->
<frame>
<a idref="frame5"/>
<b idref="frame6"/>
</frame>
<max>152</max>
<min>-152</min>
<speed>50</speed>
<axis>
<x>0</x>
<y>0</y>
<z>1</z>
</axis>
</revolute>
<!-- <origin xyz="0 0.006375 -0.21038" rpy="1.5708 -6.6954E-17 -1.6653E-16"/> -->
<fixed id="fixed7">
<frame>
<a idref="frame6"/>
<b idref="ForeArm_Link"/>
</frame>
<!-- DH params a (transl x) and alpha (rot x) for previous revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>90</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<fixed id="fixed8">
<frame>
<a idref="ForeArm_Link"/>
<b idref="frame7"/>
</frame>
<!-- DH params d (transl z) and theta (rot z) for next revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>-0.3143</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>180</z>
</rotation>
</fixed>
<revolute id="Actuator5"> <!-- type="continuous"> -->
<frame>
<a idref="frame7"/>
<b idref="frame8"/>
</frame>
<max>9999</max>
<min>-9999</min>
<speed>50</speed>
<axis>
<x>0</x>
<y>0</y>
<z>1</z>
</axis>
</revolute>
<!-- <origin xyz="0 -0.20843 -0.006375" rpy="-1.5708 2.2204E-16 -6.373E-17"/> -->
<fixed id="fixed9">
<frame>
<a idref="frame8"/>
<b idref="SphericalWrist1_Link"/>
</frame>
<!-- DH params a (transl x) and alpha (rot x) for previous revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>90</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<fixed id="fixed10">
<frame>
<a idref="SphericalWrist1_Link"/>
<b idref="frame9"/>
</frame>
<!-- DH params d (transl z) and theta (rot z) for next revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>180</z>
</rotation>
</fixed>
<revolute id="Actuator6"> <!-- type="revolute"> -->
<frame>
<a idref="frame9"/>
<b idref="frame10"/>
</frame>
<max>138</max>
<min>-138</min>
<speed>50</speed>
<axis>
<x>0</x>
<y>0</y>
<z>1</z>
</axis>
</revolute>
<!-- <origin xyz="0 0.00017505 -0.10593" rpy="1.5708 9.2076E-28 -8.2157E-15"/> -->
<fixed id="fixed11">
<frame>
<a idref="frame10"/>
<b idref="SphericalWrist2_Link"/>
</frame>
<!-- DH params a (transl x) and alpha (rot x) for previous revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>90</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<fixed id="fixed12">
<frame>
<a idref="SphericalWrist2_Link"/>
<b idref="frame11"/>
</frame>
<!-- DH params d (transl z) and theta (rot z) for next revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>-0.1674</z>
</translation>
<rotation>
<x>0</x>
<y>0</y>
<z>180</z>
</rotation>
</fixed>
<revolute id="Actuator7"> <!-- type="continuous"> -->
<frame>
<a idref="frame11"/>
<b idref="frame12"/>
</frame>
<max>9999</max>
<min>-9999</min>
<speed>50</speed>
<axis>
<x>0</x>
<y>0</y>
<z>1</z>
</axis>
</revolute>
<!-- <origin xyz="0 -0.10593 -0.00017505" rpy="-1.5708 -5.5511E-17 9.6396E-17"/> -->
<fixed id="fixed13">
<frame>
<a idref="frame12"/>
<b idref="Bracelet_Link"/>
</frame>
<!-- DH params a (transl x) and alpha (rot x) for previous revolute -->
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
<rotation>
<x>180</x>
<y>0</y>
<z>0</z>
</rotation>
</fixed>
<fixed id="fixed14">
<frame>
<a idref="Bracelet_Link"/>
<b idref="frame13"/>
</frame>
<rotation>
<x>0</x>
<y>0</y>
<z>0</z>
</rotation>
<translation>
<x>0</x>
<y>0</y>
<z>0</z>
</translation>
</fixed>
<!-- Only needed if we add an end effector <frame id="frame14"/>
<body id="EndEffector_Link"/> -->
<!-- <revolute id="EndEffector"> -->
<!-- type="fixed"> -->
<!-- <frame>
<a idref="Bracelet_Link"/>
<b idref="EndEffector_Link"/>
</frame>
<axis>
<x>0</x>
<y>0</y>
<z>0</z>
</axis>
</revolute> -->
<!-- <origin xyz="0 0 -0.0615250000000001" rpy="3.14159265358979 1.09937075168372E-32 0"/> -->
</model>
</rlmdl>
I only needed it for kinematics calcs, so I've only checked the DH parameters, probably loads of things not correct elsewhere... Compared to the documentation in the User Guide, they assumed a worldframe with Z pointing downwards, so I accounted for that with just inverting the Z translation from the DH d param instead on <fixed id="fixed_base"> .
There was an issue in rl::mdl::UrdfFactory in 0.7.0 when parsing continuous joints that has been fixed in 9bcf3e7eb05deeb7d998aa3a2d10891962003031. The current version on the master branch should work. This also includes a rl::sg::UrdfFactory for parsing the geometry information in the URDF file. After fixing the mesh filenames to relative paths and the correct files, you can use this in rlCoachMdl:
I'll have a look into adding a full model for the Gen3 Kinova arm including geometry if there are no more issues with the Gen2 version, as this seems to be interesting for some users.