Skip to content

Latest commit

 

History

History
209 lines (144 loc) · 7.81 KB

MobileManipulatorUrdfAssets.md

File metadata and controls

209 lines (144 loc) · 7.81 KB

OCS2 Mobile Manipulator

The ocs2_mobile_manipulator package supports various robotic arms and wheel-based mobile manipulators. The system model is determined by parsing the URDF and the task file.

Over here, we specify the steps involved in creating the URDF used for the examples.

Franka Panda

  • In the src directory of your catkin workspace, clone the official repository of the Franka Panda:
git clone [email protected]:frankaemika/franka_ros.git
  • Build the necessary packages and source the workspace:
catkin build franka_description ocs2_robotic_assets

source devel/setup.bash
  • Convert the xacro file to urdf format:
rosrun xacro xacro -o $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/franka/urdf/panda.urdf $(rospack find franka_description)/robots/panda_arm.urdf.xacro hand:=true
  • Copy all meshes from franka_description to ocs2_robotic_assets/resources directory:
cp -r $(rospack find franka_description)/meshes $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/franka/meshes
  • Replace the meshes locations in the robot's urdf
sed -i 's+franka_description+ocs2_robotic_assets/resources/mobile_manipulator/franka+g' $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/franka/urdf/panda.urdf
  • Add a dummy link "root" to the URDF (KDL prefers the root of the tree to have an empty-link):
  ...
  <!-- Root link -->
  <link name="root"/>
  <joint name="root_joint" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="root"/>
    <child link="panda_link0"/>
  </joint>
  <!-- Robot Arm -->
  ...

Kinova Jaco2

  • In the src directory of your catkin workspace, clone the official repository of the Kinova Jaco2:
git clone [email protected]:Kinovarobotics/kinova-ros.git
  • Build the necessary packages and source the workspace:
catkin build kinova_description ocs2_robotic_assets

source devel/setup.bash
  • Convert the xacro file to urdf format:
# For Kinova Jaco2 (7-DOF)
rosrun xacro xacro -o $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/kinova/urdf/j2n7s300.urdf $(rospack find kinova_description)/urdf/j2n7s300_standalone.xacro
# For Kinova Jaco2 (6-DOF)
rosrun xacro xacro -o $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/kinova/urdf/j2n6s300.urdf $(rospack find kinova_description)/urdf/j2n6s300_standalone.xacro
  • Copy all meshes from franka_description to ocs2_robotic_assets/resources directory:
cp -r $(rospack find kinova_description)/meshes $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/kinova/meshes
  • Replace the meshes locations in the robot's urdf
# For Kinova Jaco2 (7-DOF)
sed -i 's+kinova_description+ocs2_robotic_assets/resources/mobile_manipulator/kinova+g' $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/kinova/urdf/j2n7s300.urdf
# For Kinova Jaco2 (6-DOF)
sed -i 's+kinova_description+ocs2_robotic_assets/resources/mobile_manipulator/kinova+g' $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/kinova/urdf/j2n6s300.urdf
  • In addition to above, we make the following changes to the URDF Wto make it more readable:

    • Replace all arm joint types from "continuous" to "revolute" with high joint limits
    • (optional) Removed all gazebo tags, i.e.: <gazebo>, <transmission>
    • (optional) Removed the following links from the chain: world

Willow Garage PR2

  • In the src directory of your catkin workspace, clone the official repository of the PR2 robot:
git clone [email protected]:PR2/pr2_common.git
  • Build the necessary packages and source the workspace:
catkin build pr2_description ocs2_robotic_assets

source devel/setup.bash
  • Convert the xacro file to urdf format:
rosrun xacro xacro -o $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/pr2/urdf/pr2.urdf $(rospack find franka_description)/robots/pr2.urdf.xacro
  • Copy all meshes from pr2_description to ocs2_robotic_assets/resources directory:
cp -r $(rospack find pr2_description)/meshes $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/pr2/meshes
cp -r $(rospack find pr2_description)/materials $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/pr2/materials
  • Replace the meshes locations in the robot's urdf
sed -i 's+pr2_description+ocs2_robotic_assets/resources/mobile_manipulator/pr2+g' $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/pr2/urdf/pr2.urdf
  • In addition to above, we make the following changes to the URDF Wto make it more readable:

    • Replace all arm joint types from "continuous" to "revolute" with high joint limits
    • Changed all "screw" joints (i.e. l_gripper_motor_screw_joint, r_gripper_motor_screw_joint, torso_lift_motor_screw_link) to fixed joints
    • (optional) Removed all gazebo tags, i.e.: <gazebo>, <transmission>

Clearpath Ridgeback with UR-5

  • In the src directory of your catkin workspace, clone the official repository for the Ridgeback:
git clone https://github.com/ridgeback/ridgeback_manipulation.git --recursive
git clone https://github.com/ridgeback/ridgeback.git
  • In the src directory of your catkin workspace, clone the packages for the arm to use (in this case UR5):
vcs import . < ./ridgeback_manipulation/ur.rosinstall
  • Resolve all the ROS dependencies (top of your catkin workspace):
rosdep install --from-paths src --ignore-src -r -y
  • Build the necessary packages and source the workspace:
catkin build ur_description ridgeback_description ridgeback_ur_description ocs2_robotic_assets

source devel/setup.bash
  • Set the arm to mount on Clearpath Ridgeback base:
source $(rospack find ridgeback_ur_description)/scripts/setup_ridgeback_ur5_envar
  • Convert the xacro file to urdf format:
rosrun xacro xacro -o $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/ridgeback_ur5/urdf/ridgeback_ur5.urdf $(rospack find ridgeback_description)/urdf/ridgeback.urdf.xacro
  • Copy all meshes from pr2_description to ocs2_robotic_assets/resources directory:
mkdir -p $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/ridgeback_ur5/meshes/base
mkdir -p $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/ridgeback_ur5/meshes/ur5
cp -r $(rospack find ridgeback_description)/meshes/* $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/ridgeback_ur5/meshes/base
cp -r $(rospack find ur_description)/meshes/ur5/* $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/ridgeback_ur5/meshes/ur5
  • Replace the meshes locations in the robot's urdf
sed -i 's+ridgeback_description/meshes+ocs2_robotic_assets/resources/mobile_manipulator/ridgeback_ur5/meshes/base+g' $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/ridgeback_ur5/urdf/ridgeback_ur5.urdf
sed -i 's+ur_description/meshes/ur5+ocs2_robotic_assets/resources/mobile_manipulator/ridgeback_ur5/meshes/ur5+g' $(rospack find ocs2_robotic_assets)/resources/mobile_manipulator/ridgeback_ur5/urdf/ridgeback_ur5.urdf
  • In addition to above, we make the following changes to the URDF Wto make it more readable:

    • Replace all wheel joint types from "continuous" to "fixed"
    • Replace front_rocker joint type from "revolute" to "fixed"
    • (optional) Removed all gazebo tags, i.e.: <gazebo>, <transmission>