<> <> ''ROS Software Maintainer: [[ROBOTIS]]'' == ROBOTIS e-Manual == * [[http://emanual.robotis.com/docs/en/platform/openmanipulator/|ROBOTIS e-Manual for OpenMANIPULATOR-X]] == ROS API == {{{ #!clearsilver CS/NodeAPI node.0 { name= open_manipulator_controller desc= This node is used to control '''!OpenMANIPULATOR-X'''. sub{ 0{ name= option type= std_msgs/String desc= This message is used to set OpenMANIPULATOR options. } 1{ name= /move_group/display_planned_path type= moveit_msgs/DisplayTrajectory desc= This message is used to subscribe a planned joint trajectory published from moveit! } 2{ name= /move_group/goal type= moveit_msgs/MoveGroup desc= This message is used to subscribe a planning option data published from moveit! } 3{ name= /execute_trajectory/goal type= moveit_msgs/ExecuteTrajectory desc= This message is used to subscribe states of trajectory execution published from moveit! } } pub{ 0{ name= states type= open_manipulator_msgs/OpenManipulatorState desc= 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''). } 1{ name= tool_name/kinematics_pose type= open_manipulator_msgs/KinematicsPose desc= 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. } 2{ name= joint_states type= sensor_msgs/JointState desc= 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. } 3{ name= joint_name_position/command type= std_msgs/Float64 desc= Messages to publish goal position of each joint to gazebo simulation node. } 4{ name= rviz/moveit/update_start_state type= std_msgs/Empty desc= A message to update start state of moveit! trajectory. } } srv{ 0{ name= goal_joint_space_path type= open_manipulator_msgs/SetJointPosition desc= 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. } 1{ name= goal_joint_space_path_to_kinematics_pose type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 2{ name= goal_joint_space_path_to_kinematics_position type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 3{ name= goal_joint_space_path_to_kinematics_orientation type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 4{ name= goal_task_space_path type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 5{ name= goal_task_space_path_position_only type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 6{ name= goal_task_space_path_orientation_only type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 7{ name= goal_joint_space_path_from_present type= open_manipulator_msgs/SetJointPosition desc= 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. } 8{ name= goal_task_space_path_from_present type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 9{ name= goal_task_space_path_from_present_position_only type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 10{ name= goal_task_space_path_from_present_orientation_only type= open_manipulator_msgs/SetKinematicsPose desc= 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. } 11{ name= goal_tool_control type= open_manipulator_msgs/SetJointPosition desc= The user can use this service to move the tool of OpenMANIPULATOR-X. } 12{ name= set_actuator_state type= open_manipulator_msgs/SetActuatorState desc= 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. } 13{ name= goal_drawing_trajectory type= open_manipulator_msgs/SetDrawingTrajectory desc= 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. } 14{ name= moveit/get_joint_position type= open_manipulator_msgs/GetJointPosition desc= This service is used when using moveit! The user can use this service to receives a joint position which is calculated by move_group. } 15{ name= moveit/get_kinematics_pose type= open_manipulator_msgs/GetKinematicsPose desc= This service is used when using moveit! The user can use this service to receives a kinematics pose which is calculated by move_group. } 16{ name= moveit/set_joint_position type= open_manipulator_msgs/SetJointPosition desc= 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. } 17{ name= moveit/set_kinematics_pose type= open_manipulator_msgs/SetKinematicsPose desc= 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. } } param{ 0{ name= use_robot_name default= open_manipulator type= std::string desc= Set manipulator name(namespace of ROS messages). } 1{ name= dynamixel_usb_port default= /dev/ttyUSB0 type= std::string desc= 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). } 2{ name= dynamixel_baud_rate default= 1000000 type= std::string desc= Set baud rate of dynamixel. } 3{ name= control_period default= 0.010 type= std::string desc= Set communication period between dynamixel and PC (control loop time). } 4{ name= use_platform default= true type= std::string desc= Set whether to use the actual OpenMANIPULATOR-X or OpenMANIPULATOR-X simulation. } 5{ name= use_moveit default= false type= std::string desc= Set whether to use MoveIt! } 6{ name= planning_group_name default= arm type= std::string desc= Set planning group name set in setup_assistant. } 7{ name= moveit_sample_duration default= 0.050 type= std::string desc= Set sampling time when joint trajectory is planned from MoveIt! } } } }}}