Public Member Functions | Private Attributes | List of all members
OpenManipulator Class Reference

#include <open_manipulator_p.h>

Inheritance diagram for OpenManipulator:
Inheritance graph
[legend]

Public Member Functions

JointWaypoint angleToDistance (JointWaypoint angle)
 
JointWaypoint distanceToAngle (JointWaypoint distance)
 
void initOpenManipulator (bool using_actual_robot_state, STRING usb_port="/dev/ttyUSB0", STRING baud_rate="1000000", float control_loop_time=0.010, bool with_gripper=false)
 
 OpenManipulator ()
 
void processOpenManipulator (double present_time, bool using_actual_robot_state, bool with_gripper=false)
 
virtual ~OpenManipulator ()
 
- Public Member Functions inherited from robotis_manipulator::RobotisManipulator
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 addDynamics (Dynamics *dynamics)
 
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(), double torque_coefficient=1.0)
 
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 object_mass=0.0, Eigen::Matrix3d object_inertia_tensor=Eigen::Matrix3d::Identity(), Eigen::Vector3d object_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< JointValuegetAllActiveJointValue ()
 
std::vector< JointValuegetAllJointValue ()
 
std::vector< double > getAllToolPosition ()
 
std::vector< JointValuegetAllToolValue ()
 
DynamicPose getDynamicPose (Name component_name)
 
DynamicsgetDynamics ()
 
JointActuatorgetJointActuator (Name actuator_name)
 
std::vector< uint8_t > getJointActuatorId (Name actuator_name)
 
std::vector< JointValuegetJointGoalValueFromTrajectory (double present_time, int option=DYNAMICS_ALL_SOVING)
 
std::vector< JointValuegetJointGoalValueFromTrajectoryTickTime (double tick_time)
 
JointValue getJointValue (Name joint_name)
 
KinematicPose getKinematicPose (Name component_name)
 
KinematicsgetKinematics ()
 
ManipulatorgetManipulator ()
 
bool getMovingFailState ()
 
bool getMovingState ()
 
Pose getPose (Name component_name)
 
ToolActuatorgetToolActuator (Name actuator_name)
 
uint8_t getToolActuatorId (Name actuator_name)
 
std::vector< JointValuegetToolGoalValue ()
 
JointValue getToolValue (Name tool_name)
 
TrajectorygetTrajectory ()
 
double getTrajectoryMoveTime ()
 
Eigen::MatrixXd jacobian (Name tool_name)
 
bool makeCustomTrajectory (Name trajectory_name, Name tool_name, const void *arg, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeCustomTrajectory (Name trajectory_name, const void *arg, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeJointTrajectory (std::vector< double > goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeJointTrajectory (std::vector< JointValue > goal_joint_value, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeJointTrajectory (Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeJointTrajectory (Name tool_name, Eigen::Matrix3d goal_orientation, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeJointTrajectory (Name tool_name, KinematicPose goal_pose, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeJointTrajectoryFromPresentPosition (std::vector< double > delta_goal_joint_position, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeTaskTrajectory (Name tool_name, Eigen::Vector3d goal_position, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeTaskTrajectory (Name tool_name, Eigen::Matrix3d goal_orientation, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeTaskTrajectory (Name tool_name, KinematicPose goal_pose, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeTaskTrajectoryFromPresentPose (Name tool_name, Eigen::Vector3d position_meter, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeTaskTrajectoryFromPresentPose (Name tool_name, Eigen::Matrix3d orientation_meter, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeTaskTrajectoryFromPresentPose (Name tool_name, KinematicPose goal_pose_delta, double move_time, std::vector< JointValue > present_joint_value={})
 
bool makeToolTrajectory (Name tool_name, double tool_goal_position)
 
void printManipulatorSetting ()
 
std::vector< JointValuereceiveAllJointActuatorValue ()
 
std::vector< JointValuereceiveAllToolActuatorValue ()
 
JointValue receiveJointActuatorValue (Name joint_component_name)
 
std::vector< JointValuereceiveMultipleJointActuatorValue (std::vector< Name > joint_component_name)
 
std::vector< JointValuereceiveMultipleToolActuatorValue (std::vector< Name > tool_component_name)
 
JointValue receiveToolActuatorValue (Name tool_component_name)
 
void resetMovingFailState ()
 
 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 setDynamicsEnvironments (STRING param_name, const void *arg)
 
void setDynamicsOption (STRING param_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 setTorqueCoefficient (Name component_name, double torque_coefficient)
 
bool sleepTrajectory (double wait_time, std::vector< JointValue > present_joint_value={})
 
void solveForwardDynamics (std::map< Name, double > joint_torque)
 
void solveForwardKinematics ()
 
void solveForwardKinematics (std::vector< JointValue > *goal_joint_value)
 
bool solveGravityTerm (std::map< Name, double > *joint_torque)
 
bool solveInverseDynamics (std::map< Name, double > *joint_torque)
 
bool solveInverseKinematics (Name tool_name, Pose goal_pose, std::vector< JointValue > *goal_joint_value)
 
void stopMoving ()
 
virtual ~RobotisManipulator ()
 

Private Attributes

robotis_manipulator::JointActuatoractuator_
 
robotis_manipulator::CustomTaskTrajectorycustom_trajectory_ [CUSTOM_TRAJECTORY_SIZE]
 
robotis_manipulator::Kinematicskinematics_
 
robotis_manipulator::ToolActuatortool_
 

Detailed Description

Definition at line 39 of file open_manipulator_p.h.

Constructor & Destructor Documentation

OpenManipulator::OpenManipulator ( )

Definition at line 21 of file open_manipulator_p.cpp.

OpenManipulator::~OpenManipulator ( )
virtual

Definition at line 23 of file open_manipulator_p.cpp.

Member Function Documentation

JointWaypoint OpenManipulator::angleToDistance ( JointWaypoint  angle)

Definition at line 309 of file open_manipulator_p.cpp.

JointWaypoint OpenManipulator::distanceToAngle ( JointWaypoint  distance)

Definition at line 294 of file open_manipulator_p.cpp.

void OpenManipulator::initOpenManipulator ( bool  using_actual_robot_state,
STRING  usb_port = "/dev/ttyUSB0",
STRING  baud_rate = "1000000",
float  control_loop_time = 0.010,
bool  with_gripper = false 
)

Definition at line 32 of file open_manipulator_p.cpp.

void OpenManipulator::processOpenManipulator ( double  present_time,
bool  using_actual_robot_state,
bool  with_gripper = false 
)

Definition at line 253 of file open_manipulator_p.cpp.

Member Data Documentation

robotis_manipulator::JointActuator* OpenManipulator::actuator_
private

Definition at line 44 of file open_manipulator_p.h.

robotis_manipulator::CustomTaskTrajectory* OpenManipulator::custom_trajectory_[CUSTOM_TRAJECTORY_SIZE]
private

Definition at line 46 of file open_manipulator_p.h.

robotis_manipulator::Kinematics* OpenManipulator::kinematics_
private

Definition at line 43 of file open_manipulator_p.h.

robotis_manipulator::ToolActuator* OpenManipulator::tool_
private

Definition at line 45 of file open_manipulator_p.h.


The documentation for this class was generated from the following files:


open_manipulator_p_libs
Author(s): Ryan Shim , Yong-Ho Na , Hye-Jong KIM
autogenerated on Thu Oct 22 2020 03:16:37