|
void | initOpenManipulator (bool using_actual_robot_state, STRING usb_port="/dev/ttyUSB0", STRING baud_rate="1000000", float control_loop_time=0.010) |
|
| OpenManipulator () |
|
void | processOpenManipulator (double present_time) |
|
virtual | ~OpenManipulator () |
|
void | addComponentChild (Name my_name, Name child_name) |
|
void | addCustomTrajectory (Name trajectory_name, CustomJointTrajectory *custom_trajectory) |
|
void | addCustomTrajectory (Name trajectory_name, CustomTaskTrajectory *custom_trajectory) |
|
void | addJoint (Name my_name, Name parent_name, Name child_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, Eigen::Vector3d axis_of_rotation=Eigen::Vector3d::Zero(), int8_t joint_actuator_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double mass=0.0, Eigen::Matrix3d inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d center_of_mass=Eigen::Vector3d::Zero()) |
|
void | addJointActuator (Name actuator_name, JointActuator *joint_actuator, std::vector< uint8_t > id_array, const void *arg) |
|
void | addKinematics (Kinematics *kinematics) |
|
void | addTool (Name my_name, Name parent_name, Eigen::Vector3d relative_position, Eigen::Matrix3d relative_orientation, int8_t tool_id=-1, double max_position_limit=M_PI, double min_position_limit=-M_PI, double coefficient=1.0, double mass=0.0, Eigen::Matrix3d inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d center_of_mass=Eigen::Vector3d::Zero()) |
|
void | addToolActuator (Name tool_name, ToolActuator *tool_actuator, uint8_t id, const void *arg) |
|
void | addWorld (Name world_name, Name child_name, Eigen::Vector3d world_position=Eigen::Vector3d::Zero(), Eigen::Matrix3d world_orientation=Eigen::Matrix3d::Identity()) |
|
bool | checkJointLimit (Name component_name, double position) |
|
bool | checkJointLimit (Name component_name, JointValue value) |
|
bool | checkJointLimit (std::vector< Name > component_name, std::vector< double > position_vector) |
|
bool | checkJointLimit (std::vector< Name > component_name, std::vector< JointValue > value_vector) |
|
void | disableActuator (Name actuator_name) |
|
void | disableAllActuator () |
|
void | disableAllJointActuator () |
|
void | disableAllToolActuator () |
|
void | enableActuator (Name actuator_name) |
|
void | enableAllActuator () |
|
void | enableAllJointActuator () |
|
void | enableAllToolActuator () |
|
bool | getActuatorEnabledState (Name actuator_name) |
|
std::vector< JointValue > | getAllActiveJointValue () |
|
std::vector< JointValue > | getAllJointValue () |
|
std::vector< double > | getAllToolPosition () |
|
std::vector< JointValue > | getAllToolValue () |
|
DynamicPose | getDynamicPose (Name component_name) |
|
std::vector< uint8_t > | getJointActuatorId (Name actuator_name) |
|
std::vector< JointValue > | getJointGoalValueFromTrajectory (double present_time) |
|
std::vector< JointValue > | getJointGoalValueFromTrajectoryTickTime (double tick_time) |
|
JointValue | getJointValue (Name joint_name) |
|
KinematicPose | getKinematicPose (Name component_name) |
|
Manipulator * | getManipulator () |
|
bool | getMovingState () |
|
Pose | getPose (Name component_name) |
|
uint8_t | getToolActuatorId (Name actuator_name) |
|
std::vector< JointValue > | getToolGoalValue () |
|
JointValue | getToolValue (Name tool_name) |
|
double | getTrajectoryMoveTime () |
|
Eigen::MatrixXd | jacobian (Name tool_name) |
|
void | makeCustomTrajectory (Name trajectory_name, Name tool_name, const void *arg, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeCustomTrajectory (Name trajectory_name, const void *arg, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeJointTrajectory (Name tool_name, KinematicPose goal_pose, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeJointTrajectory (std::vector< double > goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeJointTrajectory (std::vector< JointValue > goal_joint_value, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeJointTrajectory (Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeJointTrajectory (Name tool_name, Eigen::Matrix3d goal_orientation, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeJointTrajectoryFromPresentPosition (std::vector< double > delta_goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeTaskTrajectory (Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeTaskTrajectory (Name tool_name, Eigen::Matrix3d goal_orientation, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeTaskTrajectory (Name tool_name, KinematicPose goal_pose, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeTaskTrajectoryFromPresentPose (Name tool_name, Eigen::Vector3d position_meter, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeTaskTrajectoryFromPresentPose (Name tool_name, Eigen::Matrix3d orientation_meter, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeTaskTrajectoryFromPresentPose (Name tool_name, KinematicPose goal_pose_delta, double move_time, std::vector< JointValue > present_joint_value={}) |
|
void | makeToolTrajectory (Name tool_name, double tool_goal_position) |
|
void | printManipulatorSetting () |
|
std::vector< JointValue > | receiveAllJointActuatorValue () |
|
std::vector< JointValue > | receiveAllToolActuatorValue () |
|
JointValue | receiveJointActuatorValue (Name joint_component_name) |
|
std::vector< JointValue > | receiveMultipleJointActuatorValue (std::vector< Name > joint_component_name) |
|
std::vector< JointValue > | receiveMultipleToolActuatorValue (std::vector< Name > tool_component_name) |
|
JointValue | receiveToolActuatorValue (Name tool_component_name) |
|
| RobotisManipulator () |
|
bool | sendAllJointActuatorValue (std::vector< JointValue > value_vector) |
|
bool | sendAllToolActuatorValue (std::vector< JointValue > value_vector) |
|
bool | sendJointActuatorValue (Name joint_component_name, JointValue value) |
|
bool | sendMultipleJointActuatorValue (std::vector< Name > joint_component_name, std::vector< JointValue > value_vector) |
|
bool | sendMultipleToolActuatorValue (std::vector< Name > tool_component_name, std::vector< JointValue > value_vector) |
|
bool | sendToolActuatorValue (Name tool_component_name, JointValue value) |
|
void | setCustomTrajectoryOption (Name trajectory_name, const void *arg) |
|
void | setJointActuatorMode (Name actuator_name, std::vector< uint8_t > id_array, const void *arg) |
|
void | setKinematicsOption (const void *arg) |
|
void | setToolActuatorMode (Name actuator_name, const void *arg) |
|
void | sleepTrajectory (double wait_time, std::vector< JointValue > present_joint_value={}) |
|
void | solveForwardKinematics () |
|
bool | solveInverseKinematics (Name tool_name, Pose goal_pose, std::vector< JointValue > *goal_joint_value) |
|
virtual | ~RobotisManipulator () |
|