Show EOL distros: 

open_manipulator: open_manipulator_control_gui | open_manipulator_controller | open_manipulator_description | open_manipulator_libs | open_manipulator_moveit | open_manipulator_teleop

Package Summary

OpenManipulator controller package

open_manipulator: open_manipulator_control_gui | open_manipulator_controller | open_manipulator_description | open_manipulator_libs | open_manipulator_teleop

Package Summary

OpenManipulator controller package

ROS Software Maintainer: ROBOTIS

ROBOTIS e-Manual

ROS API

open_manipulator_controller

This node is used to control !OpenMANIPULATOR-X.

Subscribed Topics

option (std_msgs/String)
  • This message is used to set OpenMANIPULATOR options.
/move_group/display_planned_path (moveit_msgs/DisplayTrajectory)
  • This message is used to subscribe a planned joint trajectory published from moveit!
/move_group/goal (moveit_msgs/MoveGroup)
  • This message is used to subscribe a planning option data published from moveit!
/execute_trajectory/goal (moveit_msgs/ExecuteTrajectory)
  • This message is used to subscribe states of trajectory execution published from moveit!

Published Topics

states (open_manipulator_msgs/OpenManipulatorState)
  • It is a message indicating the status of OpenMANIPULATOR-X. open_manipulator_actuator_state indicates whether actuators (Dynamixels) are enabled (ACTUATOR_ENABLE) or disabled (ACTUATOR_DISABLE). open_manipulator_moving_state indicates whether OpenMANIPULATOR-X is moving along the trajectory (IS_MOVING) or stopped (STOPPED).
tool_name/kinematics_pose (open_manipulator_msgs/KinematicsPose)
  • It is a message indicating pose (position and orientation) in task space. position indicates the x, y and z values of the center of the end-effector (tool). Orientation indicates the direction of the end-effector (tool) as quaternion.
joint_states (sensor_msgs/JointState)
  • It is a message indicating the states of joints of OpenMANIPULATOR-X. name indicates joint component names. effort shows currents of the joint Dynamixels. position and velocity indicates angles and angular velocities of joints.
joint_name_position/command (std_msgs/Float64)
  • Messages to publish goal position of each joint to gazebo simulation node.
rviz/moveit/update_start_state (std_msgs/Empty)
  • A message to update start state of moveit! trajectory.

Services

goal_joint_space_path (open_manipulator_msgs/SetJointPosition)
  • The user can use this service to create a trajectory in the joint space. The user inputs the angle of the target joint and the total time of the trajectory.
goal_joint_space_path_to_kinematics_pose (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory in the joint space. The user inputs the kinematics pose of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_joint_space_path_to_kinematics_position (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory in the joint space. The user inputs the kinematics pose(position only) of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_joint_space_path_to_kinematics_orientation (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory in the joint space. The user inputs the kinematics pose(orientation only) of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_task_space_path (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory in the task space. The user inputs the kinematics pose of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_task_space_path_position_only (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory in the task space. The user inputs the kinematics pose(position only) of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_task_space_path_orientation_only (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory in the task space. The user inputs the kinematics pose(orientation only) of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_joint_space_path_from_present (open_manipulator_msgs/SetJointPosition)
  • The user can use this service to create a trajectory from present joint angle in the joint space. The user inputs the angle of the target joint to be changed and the total time of the trajectory.
goal_task_space_path_from_present (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory from present kinematics pose in the task space. The user inputs the kinematics pose to be changed of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_task_space_path_from_present_position_only (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory from present kinematics pose in the task space. The user inputs the kinematics pose(position only) of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_task_space_path_from_present_orientation_only (open_manipulator_msgs/SetKinematicsPose)
  • The user can use this service to create a trajectory from present kinematics pose in the task space. The user inputs the kinematics pose(orientation only) of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.
goal_tool_control (open_manipulator_msgs/SetJointPosition)
  • The user can use this service to move the tool of OpenMANIPULATOR-X.
set_actuator_state (open_manipulator_msgs/SetActuatorState)
  • The user can use this service to control the state of actucators. If the user set true at set_actuator_state valuable, the actuator will be enabled. If the user set false at set_actuator_state valuable, the actuator will be disabled.
goal_drawing_trajectory (open_manipulator_msgs/SetDrawingTrajectory)
  • The user can use this service to create a drawing trajectory. The user can create the circle, the rhombus, the heart, and the straight line trajectory.
moveit/get_joint_position (open_manipulator_msgs/GetJointPosition)
  • This service is used when using moveit! The user can use this service to receives a joint position which is calculated by move_group.
moveit/get_kinematics_pose (open_manipulator_msgs/GetKinematicsPose)
  • This service is used when using moveit! The user can use this service to receives a kinematics pose which is calculated by move_group.
moveit/set_joint_position (open_manipulator_msgs/SetJointPosition)
  • This service is used when using moveit! The user can use this service to create a trajectory in the joint space by move_group. The user inputs the angle of the target joint and the total time of the trajectory.
moveit/set_kinematics_pose (open_manipulator_msgs/SetKinematicsPose)
  • This service is used when using moveit! The user can use this service to create a trajectory in the task space by move_group. The user inputs the kinematics pose of the OpenMANIPULATOR-X end-effector(tool) in the task space and the total time of the trajectory.

Parameters

use_robot_name (std::string, default: open_manipulator)
  • Set manipulator name(namespace of ROS messages).
dynamixel_usb_port (std::string, default: /dev/ttyUSB0)
  • Set use port to connected with Dynamixel of OpenMANIPULATOR-X. If you use U2D2, it should be set /dev/ttyUSB@. If you use OpenCR, it should be set /dev/ttyACM@ (@ indicates the port number connected to the Dynamixel).
dynamixel_baud_rate (std::string, default: 1000000)
  • Set baud rate of dynamixel.
control_period (std::string, default: 0.010)
  • Set communication period between dynamixel and PC (control loop time).
use_platform (std::string, default: true)
  • Set whether to use the actual OpenMANIPULATOR-X or OpenMANIPULATOR-X simulation.
use_moveit (std::string, default: false) planning_group_name (std::string, default: arm)
  • Set planning group name set in setup_assistant.
moveit_sample_duration (std::string, default: 0.050)
  • Set sampling time when joint trajectory is planned from MoveIt!

Wiki: open_manipulator_controller (last edited 2019-04-30 07:49:08 by Hyejong Kim)