Go to the documentation of this file.
19 #ifndef ROBOTIS_MANIPULATOR_COMMON_H
20 #define ROBOTIS_MANIPULATOR_COMMON_H
23 #if defined(__OPENCR__)
28 #include <eigen3/Eigen/Eigen>
29 #include <eigen3/Eigen/LU>
47 typedef struct _KinematicPose
53 typedef struct _Dynamicvector
59 typedef struct _DynamicPose
134 std::vector<Name>
child;
146 Eigen::Vector3d
axis;
219 Eigen::Vector3d world_position = Eigen::Vector3d::Zero(),
220 Eigen::Matrix3d world_orientation = Eigen::Matrix3d::Identity());
225 Eigen::Vector3d relative_position,
226 Eigen::Matrix3d relative_orientation,
227 Eigen::Vector3d axis_of_rotation = Eigen::Vector3d::Zero(),
228 int8_t joint_actuator_id = -1,
229 double max_position_limit = M_PI,
230 double min_position_limit = -M_PI,
231 double coefficient = 1.0,
233 Eigen::Matrix3d inertia_tensor = Eigen::Matrix3d::Identity(),
234 Eigen::Vector3d center_of_mass = Eigen::Vector3d::Zero(),
235 double torque_coefficient = 1.0);
239 Eigen::Vector3d relative_position,
240 Eigen::Matrix3d relative_orientation,
242 double max_position_limit = M_PI,
243 double min_position_limit = -M_PI,
244 double coefficient = 1.0,
246 Eigen::Matrix3d inertia_tensor = Eigen::Matrix3d::Identity(),
247 Eigen::Vector3d center_of_mass = Eigen::Vector3d::Zero(),
248 double torque_coefficient = 1.0);
359 #endif // ROBOTIS_MANIPULATOR_COMMON_H
void setAllActiveJointPosition(std::vector< double > joint_position_vector)
void setComponentKinematicPoseFromWorld(Name component_name, KinematicPose pose_to_world)
struct robotis_manipulator::_Relative Relative
void setJointValue(Name name, JointValue joint_value)
Name findComponentNameUsingId(int8_t id)
Eigen::Vector3d acceleration
std::vector< Name > getComponentChildName(Name component_name)
void setWorldOrientation(Eigen::Matrix3d world_orientation)
void setWorldPosition(Eigen::Vector3d world_position)
struct robotis_manipulator::_Force Force
enum robotis_manipulator::_ComponentType ComponentType
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(), double torque_coefficient=1.0)
std::vector< JointValue > getAllToolValue()
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)
struct robotis_manipulator::_Dynamicvector Dynamicvector
struct robotis_manipulator::_Inertia Inertia
double getJointAcceleration(Name component_name)
bool checkJointLimit(Name Component_name, double value)
struct robotis_manipulator::_World World
Eigen::Matrix3d getComponentRelativeOrientationFromParent(Name component_name)
double torque_coefficient
void setJointEffort(Name name, double effort)
Eigen::Vector3d getComponentCenterOfMass(Name component_name)
std::vector< JointValue > getAllJointValue()
ComponentType component_type
Eigen::Vector3d getComponentRelativePositionFromParent(Name component_name)
Eigen::Matrix3d inertia_tensor
double getJointEffort(Name component_name)
void setJointVelocity(Name name, double velocity)
double getTorqueCoefficient(Name component_name)
JointValue getJointValue(Name component_name)
Eigen::Vector3d getWorldPosition()
struct robotis_manipulator::_Moment Moment
struct robotis_manipulator::_Point Point
double getJointPosition(Name component_name)
std::vector< Name > getAllToolComponentName()
enum robotis_manipulator::_TrajectoryType TrajectoryType
void addComponentChild(Name my_name, Name child_name)
void setAllJointPosition(std::vector< double > joint_position_vector)
Component getComponent(Name component_name)
struct robotis_manipulator::_Point ToolValue
void setAllJointValue(std::vector< JointValue > joint_value_vector)
struct robotis_manipulator::_DynamicPose DynamicPose
Pose getComponentPoseFromWorld(Name component_name)
bool setPositionToValue(std::vector< JointValue > *value, std::vector< double > position)
struct robotis_manipulator::_JointConstant JointConstant
void setWorldKinematicPose(KinematicPose world_kinematic_pose)
JointConstant joint_constant
std::vector< JointValue > getAllActiveJointValue()
struct robotis_manipulator::_Point JointValue
double getJointVelocity(Name component_name)
void setJointAcceleration(Name name, double acceleration)
void setComponentPoseFromWorld(Name component_name, Pose pose_to_world)
std::map< Name, Component >::iterator getIteratorEnd()
void setWorldLinearAcceleration(Eigen::Vector3d world_linear_acceleration)
Eigen::Vector3d getAxis(Name component_name)
struct robotis_manipulator::_Time Time
std::map< Name, Component > getAllComponent()
std::vector< uint8_t > getAllActiveJointID()
void setWorldAngularAcceleration(Eigen::Vector3d world_angular_acceleration)
struct robotis_manipulator::_KinematicPose KinematicPose
std::vector< uint8_t > getAllJointID()
void setComponentPositionFromWorld(Name component_name, Eigen::Vector3d position_to_world)
Eigen::Vector3d getComponentPositionFromWorld(Name component_name)
KinematicPose getWorldKinematicPose()
void setTorqueCoefficient(Name component_name, double torque_coefficient)
void setJointPosition(Name name, double position)
std::vector< Name > child
struct robotis_manipulator::_Point ActuatorValue
DynamicPose getWorldDynamicPose()
int8_t getId(Name component_name)
void setComponentDynamicPoseFromWorld(Name component_name, DynamicPose dynamic_pose)
void setAllToolValue(std::vector< JointValue > tool_value_vector)
@ CUSTOM_JOINT_TRAJECTORY
struct robotis_manipulator::_TaskWaypoint TaskWaypoint
std::vector< double > getAllJointPosition()
KinematicPose getComponentKinematicPoseFromWorld(Name component_name)
void setWorldLinearVelocity(Eigen::Vector3d world_linear_velocity)
std::map< Name, Component > component_
KinematicPose getComponentRelativePoseFromParent(Name component_name)
void setComponent(Name component_name, Component component)
std::vector< double > getAllActiveJointPosition()
Name getComponentParentName(Name component_name)
void setWorldDynamicPose(DynamicPose world_dynamic_pose)
void setComponentActuatorName(Name component_name, Name actuator_name)
@ PASSIVE_JOINT_COMPONENT
bool setEffortToValue(std::vector< JointValue > *value, std::vector< double > effort)
void setWorldPose(Pose world_pose)
void setAllToolPosition(std::vector< double > tool_position_vector)
struct robotis_manipulator::_Component Component
std::vector< Name > getAllActiveJointComponentName()
std::vector< double > getAllToolPosition()
void setComponentOrientationFromWorld(Name component_name, Eigen::Matrix3d orientation_to_wolrd)
Name getComponentActuatorName(Name component_name)
struct robotis_manipulator::_Object Object
void setAllActiveJointValue(std::vector< JointValue > joint_value_vector)
Eigen::Matrix3d orientation
KinematicPose pose_from_parent
void printManipulatorSetting()
struct robotis_manipulator::_Limit Limit
Eigen::Vector3d center_of_mass
std::vector< JointValue > JointWaypoint
int8_t getComponentSize()
struct robotis_manipulator::_ChainingName ChainingName
DynamicPose getComponentDynamicPoseFromWorld(Name component_name)
double getComponentMass(Name component_name)
Eigen::Matrix3d getComponentInertiaTensor(Name component_name)
void addWorld(Name world_name, Name child_name, Eigen::Vector3d world_position=Eigen::Vector3d::Zero(), Eigen::Matrix3d world_orientation=Eigen::Matrix3d::Identity())
struct robotis_manipulator::_TaskWaypoint Pose
Eigen::Matrix3d getComponentOrientationFromWorld(Name component_name)
double getCoefficient(Name component_name)
std::map< Name, Component >::iterator getIteratorBegin()
void setWorldAngularVelocity(Eigen::Vector3d world_angular_velocity)
bool checkComponentType(Name component_name, ComponentType component_type)
Eigen::Matrix3d getWorldOrientation()
robotis_manipulator
Author(s): Hye-Jong KIM
, Darby Lim , Yong-Ho Na , Ryan Shim
autogenerated on Wed Mar 2 2022 00:50:56