<> <> ''ROS Software Maintainer: [[ROBOTIS|ROBOTIS]]'' == ROBOTIS e-Manual == * [[http://emanual.robotis.com/docs/en/platform/openmanipulator/|ROBOTIS e-Manual for OpenMANIPULATOR-X]] == ROS Message Types == '''!JointPosition.msg''' <
> This message has (string[]) ''joint_name'', (float64[]) ''position'', (float64) ''max_accelerations_scaling_factor'' and (float64) ''max_velocity_scaling_factor''. '''!KinematicsPose.msg''' <
> This message has (geometry_msgs/Pose) ''pose'', (float64) ''max_accelerations_scaling_factor'', (float64) ''max_velocity_scaling_factor'' and (float64) ''tolerance''. '''!OpenManipulatorState.msg''' <
> This message shows robot state. It has (string) ''open_manipulator_moving_state'' and (string) ''open_manipulator_actuator_state''. == ROS Service Types == '''!GetJointPosition.srv''' <
> Set (string) ''planning_group'',<
> and get (!JointPosition) ''joint_position''. '''!GetKinematicsPose.srv''' <
> Set (string) ''planning_group'' and (string) ''end_effector_name'',<
> and get (!KinematicsPose) ''kinematics_pose'' and (Header) ''header''. '''!SetActuatorState.srv''' <
> Set (bool) ''set_actuator_state'',<
> and get (bool) ''is_planned''. '''!SetDrawingTrajectory.srv''' <
> Set (string) ''end_effector_name'', (string) ''drawing_trajectory_name'', (float64[]) ''param'' and (float64) ''path_time'',<
> and get (bool) ''is_planned''. '''!SetJointPosition.srv''' <
> Set (string) ''planning_group'', (!JointPosition) ''joint_position'' and (float64) ''path_time'',<
> and get (bool) ''is_planned''. '''!SetKinematicsPose.srv''' <
> Set (string) ''planning_group'', (string) ''end_effector_name'', (!KinematicsPose) ''kinematics_pose'' and (float64) ''path_time'',<
> and get (bool) ''is_planned''.