raisimTech / raisimLib

Visit www.raisim.com
http://www.raisim.com
Other
341 stars 91 forks source link

Problem the show the robot in raisimunity #489

Closed Lr-2002 closed 1 year ago

Lr-2002 commented 1 year ago

I'm using the raisim to show my urdf model on Ubuntu with raisimUnity. The urdf was written by myself . The Ros could show the model correctly while the RaisimUnity has no image.

This is the urdf model:

<?xml version="1.0"?>
<robot name="leg">
  <link name="base_link"/>

  <joint name="world_to_leg" type="fixed">
    <axis xyz="0 0 0"/>
    <origin xyz="0.0 0.0 1.5" rpy="1.57 0 0"/>
    <parent link="base_link"/>
    <child link="lk1"/>
  </joint>

  <link name="lk1">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.05" length="0.1"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="1"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  <link name="lk2">
    <visual>
      <origin xyz="0 0 0.25" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.05" length="0.5"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="5"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  <link name="lk3">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.05" length="0.10"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="1"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  <link name="lk4">
    <visual>
      <origin xyz="0 0 0.2" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.05" length="0.4"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="4"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  <link name="lk5">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.05" length="0.10"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="1"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  <link name="lk6">
    <visual>
      <origin xyz="0 0 0.15" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.05" length="0.3"/>
      </geometry>
    </visual>
    <inertial>
      <mass value="3"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  <joint name="r1" type="revolute">
    <axis xyz="0 1 0"/>
    <parent link="lk1"/>
    <child link="lk2"/>
    <origin xyz="0.0 0 0" rpy="1.57 0 0"/>
    <limit lower="-1.57" upper="1.57" effort="10" velocity="3"/>
    <dynamics spring_mount="0.5" stiffness="150.0" damping="20."/>
  </joint>

  <joint name="r2" type="revolute">
    <axis xyz="0 0 1"/>
    <parent link="lk2"/>
    <child link="lk3"/>
    <origin xyz="0 0 0.5" rpy="1.57 0 0 "/>
    <limit lower="-1.57" upper="1.57" effort="10" velocity="3"/>
    <dynamics spring_mount="0.5" stiffness="150.0" damping="20."/>
  </joint>

  <joint name="r_1" type="fixed">
    <axis xyz="0 1 0"/>
    <parent link="lk3"/>
    <child link="lk4"/>
    <origin xyz="0.0 0.0 0.0" rpy="-1.57 0 0 "/>
  </joint>
  <joint name="r3" type="revolute">
    <axis xyz="0 0 1"/>
    <parent link="lk4"/>
    <child link="lk5"/>
    <origin xyz="0 0 0.4" rpy="1.57 0 0 "/>
    <limit lower="-1.57" upper="1.57" effort="10" velocity="3"/>
    <dynamics spring_mount="0.5" stiffness="150.0" damping="20."/>
  </joint>
  <joint name="r_2" type="fixed">
    <axis xyz="0 0 1"/>
    <parent link="lk5"/>
    <child link="lk6"/>
    <origin xyz="0 0 0" rpy="-1.57 0 0 "/>
  </joint>
</robot>

This is the image running ROS

image

This is image generated by raisimUnity image

The file to run the robot is as below:

// This file is part of RaiSim. You must obtain a valid license from RaiSim Tech
// Inc. prior to usage.

#include "raisim/RaisimServer.hpp"
#include "raisim/World.hpp"
#if WIN32
#include <timeapi.h>
#endif
#include <iostream>

int main(int argc, char* argv[]) {
    auto binaryPath = raisim::Path::setFromArgv(argv[0]);
    raisim::World::setActivationKey(binaryPath.getDirectory() + "\\rsc\\activation.raisim");
    std::cout<<"testing!" << std::endl;
    /// create raisim world
    raisim::World world;
    world.setTimeStep(0.001);

    /// create objects
    world.addGround();
    auto leg = world.addArticulatedSystem(binaryPath.getDirectory() + "\\rsc\\leg\\leg.urdf");

    /// cartPole state
    Eigen::VectorXd jointNominalConfig(leg->getGeneralizedCoordinateDim());

    jointNominalConfig.setZero();
    jointNominalConfig[1] = 0.01;
    jointNominalConfig[0] = 0.01;
    jointNominalConfig[2] = 0.01;

    leg->setGeneralizedCoordinate(jointNominalConfig);
    auto names = leg->getMovableJointNames();
    for(auto i : names){
        std::cout<< i<< std::endl;
    }
    leg->printOutBodyNamesInOrder();
    leg->printOutFrameNamesInOrder();
    leg->printOutMovableJointNamesInOrder();
    /// launch raisim server
    raisim::RaisimServer server(&world);
    server.launchServer();
    server.focusOn(leg);

    for (int i=0; i<200000; i++) {
        raisim::MSLEEP(1);
        server.integrateWorldThreadSafe();
    }

    server.killServer();
}
Lr-2002 commented 1 year ago

What's more ,the info ouput as below

testing!
ROOT
r1
r2
r3
0th body: base_link
1th body: lk2
2th body: lk3
3th body: lk5
0th frame: ROOT
1th frame: r1
2th frame: world_to_leg
3th frame: r2
4th frame: r3
5th frame: r_1
6th frame: r_2
0th body: ROOT

Could you help me PlZ

Lr-2002 commented 1 year ago

problem solved the first link must use world for its name which is same with ROS must use base_link for its first link's name

But could you add an exception on the raisim? I've seeken for it for about 1day

jhwangbo commented 1 year ago

ok, this makes sense. Thx for posting. I'll update it on the next push

jhwangbo commented 1 year ago

I'll keep it open so I don't get

Lr-2002 commented 1 year ago

okay But it's very interesting If you use the example a1, it still works while the a1.urdf has world in xacro part , which was the annotation part? Does the annotation still work?

  <!-- <xacro:include filename="$(find aliengo_gazebo)/launch/gazebo.xacro"/> -->
  <!-- Debug mode will hung up the robot, use "true" or "false" to switch it. -->
  <!-- <xacro:if value="$(arg DEBUG)">
        <link name="world"/>
        <joint name="base_static_joint" type="fixed">
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <parent link="world"/>
            <child link="base"/>
        </joint>
    </xacro:if>  -->
jhwangbo commented 1 year ago

that looks like a valid convention to me. It will work