Edit on GitHub

Message List

NOTE:
Please launch the OpenMANIPULATOR-X Controller before running this section.

The controller uses topic and service to control and check the status of OpenMANIPULATOR-X.

NOTE:
Please launch the OpenMANIPULATOR-X Controller before running this section.

The controller uses topic and service to control and check the status of OpenMANIPULATOR-X.

NOTE:
Please launch the OpenMANIPULATOR-X Controller before running this section.

The controller uses topic and service to control and check the status of OpenMANIPULATOR-X.

NOTE:
Please launch the OpenMANIPULATOR-X Controller before running this section.

The controller uses topic and service to control and check the status of OpenMANIPULATOR-X.

Topic

Topic Monitor

In order to check the topics of OpenMANIPULATOR-X controller, you can use rqt GUI tool. Rqt is a Qt-based framework for GUI development in ROS environment. Rqt allows users to easily read topics. Various information such as topic name, type, bandwidth, Hz and value are shown on the Topic monitor plugin of rqt.

$ rqt

TIP: If the Topic Monitor is not shown, select the plugin > Topics > Topic Monitor.

Unchecked Topics will not be monitored. To monitor topics, select the checkbox.

If you would like to see more details about a specific topic, click on the ▶ icon next to the checkbox to expand.

Published Topic List

A list of topics that the open_manipulator_controller publishes.

/open_manipulator/states
  • open_manipulator_msgs/OpenManipulatorState
  • The message indicating the status of OpenMANIPULATOR.
  • “open_manipulator_actuator_state” indicates whether actuators 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.
/joint_states
  • sensor_msgs/JointState
  • The message indicating the states of joints of OpenMANIPULATOR-X.
  • “name” indicates joint component names.
  • “effort” shows current consumption of each DYNAMIXEL.
  • “position” and “velocity” indicates angles and angular velocities of joints.
/open_manipulator/gripper/kinematics_pose
  • open_manipulator_msgs/KinematicsPose
  • The message that indicates a 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 rotation of the end-effector (tool) in quaternion.
/open_manipulator/joint#_position/command
  • std_msgs/Float64
  • The messages to publish goal position of each joint to gazebo simulation node.
  • joint# identifies the name of each joint.
  • The messages will be published when the controller is launched with the use_platform:=false option.
/rviz/moveit/update_start_state
  • std_msgs/Empty
  • The message to update start state of MoveIt! trajectory.
  • This message will be published when the controller is launched with the use_moveit:=true option.

NOTE: These topics are messages for checking the status of the robot regardless of the robot’s motion.

Subscribed Topic List

A list of topics that the open_manipulator_controller subscribes.

/open_manipulator/option
  • std_msgs/String
  • This topic is used when setting the OpenMANIPULATOR-X options.
  • “print_open_manipulator_setting” requests the open_manipulator_controller to display “Manipulator Description”.
/move_group/display_planned_path
/move_group/goal
/execute_trajectory/goal

NOTE: These topics are messages for checking the status of the robot regardless of the robot’s motion.

Topic Monitor

In order to check the topics of OpenMANIPULATOR-X controller, you can use rqt GUI tool. Rqt is a Qt-based framework for GUI development in ROS environment. Rqt allows users to easily read topics. Various information such as topic name, type, bandwidth, Hz and value are shown on the Topic monitor plugin of rqt.

$ rqt

TIP: If the Topic Monitor is not shown, select the plugin > Topics > Topic Monitor.

Unchecked Topics will not be monitored. To monitor topics, select the checkbox.

If you would like to see more details about a specific topic, click on the ▶ icon next to the checkbox to expand.

Published Topic List

A list of topics that the open_manipulator_controller publishes.

/states
  • open_manipulator_msgs/OpenManipulatorState
  • The message indicating the status of OpenMANIPULATOR.
  • “open_manipulator_actuator_state” indicates whether actuators 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.
/joint_states
  • sensor_msgs/JointState
  • The message indicating the states of joints of OpenMANIPULATOR-X.
  • “name” indicates joint component names.
  • “effort” shows current consumption of each DYNAMIXEL.
  • “position” and “velocity” indicates angles and angular velocities of joints.
/gripper/kinematics_pose
  • open_manipulator_msgs/KinematicsPose
  • The message that indicates a 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 rotation of the end-effector (tool) in quaternion.

NOTE: These topics are messages for checking the status of the robot regardless of the robot’s motion.

Subscribed Topic List

A list of topics that the open_manipulator_controller subscribes.

/option
  • std_msgs/String
  • This topic is used when setting the OpenMANIPULATOR-X options.
  • “print_open_manipulator_setting” requests the open_manipulator_controller to display “Manipulator Description”.
/joint_states
  • sensor_msgs/JointState
  • The message indicating the states of joints of OpenMANIPULATOR-X.
  • “name” indicates joint component names.
  • “effort” shows current consumption of each DYNAMIXEL.
  • “position” and “velocity” indicates angles and angular velocities of joints.
/gripper/kinematics_pose
  • open_manipulator_msgs/KinematicsPose
  • The message that indicates a 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 rotation of the end-effector (tool) in quaternion.

NOTE: These topics are messages for checking the status of the robot regardless of the robot’s motion.

Topic Monitor

In order to check the topics of OpenMANIPULATOR-X controller, you can use rqt GUI tool. Rqt is a Qt-based framework for GUI development in ROS environment. Rqt allows users to easily read topics. Various information such as topic name, type, bandwidth, Hz and value are shown on the Topic monitor plugin of rqt.

$ rqt

TIP: If the Topic Monitor is not shown, select the plugin > Topics > Topic Monitor.

Unchecked Topics will not be monitored. To monitor topics, select the checkbox.

If you would like to see more details about a specific topic, click on the ▶ icon next to the checkbox to expand.

Published Topic List

A list of topics that the open_manipulator_controller publishes.

/states
  • open_manipulator_msgs/msg/OpenManipulatorState
  • The message indicating the status of OpenMANIPULATOR.
  • “open_manipulator_actuator_state” indicates whether actuators 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.
/joint_states
  • sensor_msgs/msg/JointState
  • The message indicating the states of joints of OpenMANIPULATOR-X.
  • “name” indicates joint component names.
  • “effort” shows current consumption of each DYNAMIXEL.
  • “position” and “velocity” indicates angles and angular velocities of joints.
/kinematics_pose
  • open_manipulator_msgs/msg/KinematicsPose
  • The message that indicates a 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 rotation of the end-effector (tool) in quaternion.

Subscribed Topic List

A list of topics that the open_manipulator_controller subscribes.

/option
  • std_msgs/msg/String
  • This topic is used when setting the OpenMANIPULATOR-X options.
  • “print_open_manipulator_setting” requests the open_manipulator_controller to display “Manipulator Description”.

Topic Monitor

In order to check the topics of OpenMANIPULATOR-X controller, you can use rqt GUI tool. Rqt is a Qt-based framework for GUI development in ROS environment. Rqt allows users to easily read topics. Various information such as topic name, type, bandwidth, Hz and value are shown on the Topic monitor plugin of rqt.

$ rqt

TIP: If the Topic Monitor is not shown, select the plugin > Topics > Topic Monitor.

Unchecked Topics will not be monitored. To monitor topics, select the checkbox.

If you would like to see more details about a specific topic, click on the ▶ icon next to the checkbox to expand.

Published Topic List

A list of topics that the open_manipulator_controller publishes.

/states
  • open_manipulator_msgs/msg/OpenManipulatorState
  • The message indicating the status of OpenMANIPULATOR.
  • “open_manipulator_actuator_state” indicates whether actuators 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.
/joint_states
  • sensor_msgs/msg/JointState
  • The message indicating the states of joints of OpenMANIPULATOR-X.
  • “name” indicates joint component names.
  • “effort” shows current consumption of each DYNAMIXEL.
  • “position” and “velocity” indicates angles and angular velocities of joints.
/kinematics_pose
  • open_manipulator_msgs/msg/KinematicsPose
  • The message that indicates a 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 rotation of the end-effector (tool) in quaternion.

Subscribed Topic List

A list of topics that the open_manipulator_controller subscribes.

/option
  • std_msgs/msg/String
  • This topic is used when setting the OpenMANIPULATOR-X options.
  • “print_open_manipulator_setting” requests the open_manipulator_controller to display “Manipulator Description”.

Not supported

Service

Service Server List

NOTE: These services are messages to operate OpenMANIPULATOR-X or to change the status of DYNAMIXEL of OpenMANIPULATOR.

A list of service servers that open_manipulator_controller has.

/open_manipulator/goal_joint_space_path
/open_manipulator/goal_joint_space_path_to_kinematics_pose
/open_manipulator/goal_joint_space_path_to_kinematics_position
/open_manipulator/goal_joint_space_path_to_kinematics_orientation
/open_manipulator/goal_task_space_path
/open_manipulator/goal_task_space_path_position_only
/open_manipulator/goal_task_space_path_orientation_only
/open_manipulator/goal_joint_space_path_from_present
/open_manipulator/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.
/open_manipulator/goal_task_space_path_from_present_position_only
/open_manipulator/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.
/open_manipulator/goal_tool_control
/open_manipulator/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.
/open_manipulator/goal_drawing_trajectory
/moveit/get_joint_position
/moveit/get_kinematics_pose
/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.

Service Server List

NOTE: These services are messages to operate OpenMANIPULATOR-X or to change the status of DYNAMIXEL of OpenMANIPULATOR.

A list of service servers that open_manipulator_controller has.

/goal_joint_space_path
/goal_joint_space_path_to_kinematics_pose
/goal_joint_space_path_to_kinematics_position
/goal_joint_space_path_to_kinematics_orientation
/goal_task_space_path
/goal_task_space_path_position_only
/goal_task_space_path_orientation_only
/goal_joint_space_path_from_present
/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
/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
/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

Service Server List

NOTE: These services are messages to operate OpenMANIPULATOR-X or to change the status of DYNAMIXEL of OpenMANIPULATOR.

A list of service servers that open_manipulator_controller has.

/goal_joint_space_path
/goal_joint_space_path_to_kinematics_pose
/goal_joint_space_path_to_kinematics_position
/goal_joint_space_path_to_kinematics_orientation
/goal_task_space_path
/goal_task_space_path_position_only
/goal_task_space_path_orientation_only
/goal_joint_space_path_from_present
/goal_task_space_path_from_present
  • open_manipulator_msgs/srv/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
/goal_task_space_path_from_present_orientation_only
/goal_tool_control
/set_actuator_state
  • open_manipulator_msgs/srv/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

Service Server List

NOTE: These services are messages to operate OpenMANIPULATOR-X or to change the status of DYNAMIXEL of OpenMANIPULATOR.

A list of service servers that open_manipulator_controller has.

/goal_joint_space_path
/goal_joint_space_path_to_kinematics_pose
/goal_joint_space_path_to_kinematics_position
/goal_joint_space_path_to_kinematics_orientation
/goal_task_space_path
/goal_task_space_path_position_only
/goal_task_space_path_orientation_only
/goal_joint_space_path_from_present
/goal_task_space_path_from_present
  • open_manipulator_msgs/srv/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
/goal_task_space_path_from_present_orientation_only
/goal_tool_control
/set_actuator_state
  • open_manipulator_msgs/srv/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

Not supported