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
Released
Documented
OpenManipulator controller package
- Maintainer status: developed
- Maintainer: Pyo <pyo AT robotis DOT com>, Hye-Jong KIM <hjkim AT robotis DOT com>
- Author: Darby Lim <thlim AT robotis DOT com>, Hye-Jong KIM <hjkim AT robotis DOT com>, Ryan Shim <jhshim AT robotis DOT com>, Yong-Ho Na <yhna AT robotis DOT com>
- License: Apache 2.0
- Bug / feature tracker: https://github.com/ROBOTIS-GIT/open_manipulator/issues
- Source: git https://github.com/ROBOTIS-GIT/open_manipulator.git (branch: kinetic-devel)
open_manipulator: open_manipulator_control_gui | open_manipulator_controller | open_manipulator_description | open_manipulator_libs | open_manipulator_teleop
Package Summary
Released
Documented
OpenManipulator controller package
- Maintainer status: developed
- Maintainer: Will Son <willson AT robotis DOT com>
- Author: Darby Lim <thlim AT robotis DOT com>, Hye-Jong KIM <hjkim AT robotis DOT com>, Ryan Shim <jhshim AT robotis DOT com>, Yong-Ho Na <yhna AT robotis DOT com>
- License: Apache 2.0
- Bug / feature tracker: https://github.com/ROBOTIS-GIT/open_manipulator/issues
- Source: git https://github.com/ROBOTIS-GIT/open_manipulator.git (branch: melodic-devel)
Contents
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.
- This message is used to subscribe a planned joint trajectory published from moveit!
- This message is used to subscribe a planning option data published from moveit!
- 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).
- 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.
- 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.
- Messages to publish goal position of each joint to gazebo simulation node.
- 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.
- 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.
- 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.
- 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.
- 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.
- 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.
- 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.
- 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.
- 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.
- 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.
- 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.
- The user can use this service to move the tool of OpenMANIPULATOR-X.
- 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.
- 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.
- This service is used when using moveit! The user can use this service to receives a joint position which is calculated by move_group.
- This service is used when using moveit! The user can use this service to receives a kinematics pose which is calculated by move_group.
- 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.
- 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).
- 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).
- Set baud rate of dynamixel.
- Set communication period between dynamixel and PC (control loop time).
- Set whether to use the actual OpenMANIPULATOR-X or OpenMANIPULATOR-X simulation.
- Set whether to use MoveIt!
- Set planning group name set in setup_assistant.
- Set sampling time when joint trajectory is planned from MoveIt!