Edit on GitHub

ROS Reference

ROS Package Description

manipulator_h_base_module

This package describes basic function to control ROBOTIS MANIPULATOR-H. This module is based on position control.

manipulator_h_base_module_msgs

This package includes ROS messages and services for manipulator_h_base_module_msgs.

manipulator_h_bringup

This package includes launch file to describe robotis in Rviz.
launch : launch file to bring up the robot in Rviz

robotis_manipulator_description

This package includes URDF model of ROBOTIS MANIPULATOR-H. Additionally, we provide full kinematics and dynamics information of each link.
doc : document for robotis manipulator joint & link information
launch : launch file to confirm the urdf model
meshes : STL files of each link
urdf : urdf files to create robot model

robotis_manipulator_gazebo

This package provides GAZEBO simulation environment for ROBOTIS MANIPULATOR-H. We provides two controllers such as position and effort controllers.
config : yaml files of gazebo simulation controller
launch : launch files to execute gazebo simulation
worlds : world file for gazebo simulation

robotis_manipulator_gui

This package provides simple GUI to control ROBOTIS MANIPULATOR-H. This GUI is connected to manipulator_h_base_module.
GUI program using qt creater

robotis_manipulator_kinematics_dynamics

This packages provides library of kinematics and dynamics information for ROBOTIS MANIPULATOR-H. Additionally, there are some function to calculate kinematics and dynamics.

robotis_manipulator_manager

This package describes robot manager to execute manipulator_h_base_module.

ROS Message Type

ROS Message Type

ROS Service Type

ROS API

manipulator_base_module

Subscribed Topics

/robotis/base/ini_pose_msg (std_msgs/String)
   Message for initial pose

/robotis/base/set_mode_msg (std_msgs/String)
   Message for set mode

/robotis/base/joint_pose_msg (manipulator_manipulation_module_msgs/JointPose)
   Message for joint space control

/robotis/base/kinematics_pose_msg (manipulator_manipulation_module_msgs/KinematicsPose)
   Message for task space control

Published Topics

/robotis/status(robotis_controller_msgs/StatusMsg)
   Message for current state

Services

/robotis/base/get_joint_pose (manipulator_manipulation_module_msgs/GetJointPose)
   Service to read current joint value

/robotis/base/get_kinematics_pose (manipulator_manipulation_module_msgs/GetKinematicsPose)
   Service to read current end effector’s pose

manipulator_manager

Overview

manipulator_manager is a package to apply ROBOTIS Framework to ROBOTIS Manipulator.
If you want to create new manager, please refer the link as below.

Ref. : Creating new robot manager

Parameters

launch parameters

gazebo (bool, default: false)
   Select using simulation (gazebo) mode or real robot mode.

gazebo_robot_name (string, default: “”)
   robot name for joint_states topic name using gazebo mode.
   ex) If the gazebo_robot_name is robotis_manipulator, subscribing topic is
    /robotis_manipulator/joint_states.

offset_file_path (string, default: “”)
   The file path that includes joint offset information and initial pose of tuning offset.

robot_file_path (string, default: “”)
   The file .robot ‘s path that includes robot information.

manipulator_kinematics_dynamcis

Getting started

To use this library, it is necessary to set the CMakeList.txt and package.xml of each module

In CMakeList.txt,

  find_package( manipulator_kinematics_dynamics )   
  target_link_libraries( manipulator_kinematics_dynamics )   

In package.xml,

  <build_depend>manipulator_kinematics_dynamics</build_depend>   

Functions

LinkData.cpp

name : Joint name
parent : Parent joint ID
sibling : Sibling joint ID
child : Child joint ID
mass : Mass
relative_position : Joint relative position (relative to parent)
joint_axis : Joint axis vector (relative to parent)
center_of_mass : Center of mass (Link Local)
inertia : Moment of Inertia (Link Local)
joint_limit_max : Joint upper limit
joint_limit_min : Joint lower limit
joint_angle : Joint angle
joint_velocity : Joint velocity
joint_acceleration : Joint acceleration
position: Link position
orientation : Link orienataion
transformation : Link transformation matrix

ManipulatorKinematicsDynamics.cpp
  ManipulatorKinematicsDynamics(TREE_SELECT tree)
  • description : ROBOTIS MANIPULATOR joint & link information
  std::vector<int> findRoute( int to )
  • description : find kinematics tree
  • arguments : start joint id
  • return value : vector ( n x 1 )
  std::vector<int> findRoute( int from , int to )
  • description : find kinematics tree
  • arguments : start joint id and end joint id
  • return value : vector ( n x 1 )
  double TotalMass( int joint_ID )
  • description : calculate total mass
  • arguments : start joint id
  • return value : total mass
  Eigen::MatrixXd CalcMC( int joint_ID )
  Eigen::MatrixXd CalcCOM( Eigen::MatrixXd MC )
  • description : calculate center of mass
  • arguments : start joint id
  • return value : 3 x 1 matrix
  void ForwardKinematics( int joint_ID )
  • description : calculate forward kinematics
  • arguments : start joint id
  Eigen::MatrixXd CalcJacobian( std::vector<int> idx )
  • description : calculate forward kinematics
  • arguments : vector ( n x 1 )
  • return value : 6 x n matrix
  bool InverseKinematics
  ( int to,
    Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation,
    int max_iter,                 double ik_err )
  • description : calculate inverse kinematics
  • arguments : end joint id, target position, target orientation, max iteration, calculation error
  • return value : true or false
  bool InverseKinematics
  ( int from,                     int to,
    Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation,
    int max_iter,                 double ik_err )
  • description : calculate inverse kinematics
  • arguments : start joint id, end joint id, target position, target orientation, max iteration, calculation error
  • return value : true or false