19 #include "../../include/robotis_manipulator/robotis_manipulator_common.h" 25 if(value->size()==effort.size()){
26 for(
int i=0; i<value->size(); i++){
27 value->at(i).effort=effort.at(i);
38 if(value->size()==position.size()){
39 for(
int i=0; i<value->size(); i++){
40 value->at(i).position=position.at(i);
56 Eigen::Vector3d world_position,
57 Eigen::Matrix3d world_orientation)
72 Eigen::Vector3d relative_position,
73 Eigen::Matrix3d relative_orientation,
74 Eigen::Vector3d axis_of_rotation,
75 int8_t joint_actuator_id,
76 double max_position_limit,
77 double min_position_limit,
80 Eigen::Matrix3d inertia_tensor,
81 Eigen::Vector3d center_of_mass,
82 double torque_coefficient)
85 if (joint_actuator_id != -1)
96 temp_component.
name.
child.push_back(child_name);
120 component_.insert(std::make_pair(my_name, temp_component));
125 Eigen::Vector3d relative_position,
126 Eigen::Matrix3d relative_orientation,
128 double max_position_limit,
129 double min_position_limit,
132 Eigen::Matrix3d inertia_tensor,
133 Eigen::Vector3d center_of_mass,
134 double torque_coefficient)
164 component_.insert(std::make_pair(my_name, temp_component));
169 component_.at(my_name).name.child.push_back(child_name);
174 log::println(
"----------<Manipulator Description>----------");
197 std::vector<double> result_vector;
198 std::map<Name, Component>::iterator it_component;
205 log::println(
" [Component Type]\n Active Joint");
207 log::println(
" [Component Type]\n Passive Joint");
209 log::println(
" [Component Type]\n Tool");
212 for(uint32_t index = 0; index <
component_.at(it_component->first).name.child.size(); index++)
228 log::print(
" Maximum :",
component_.at(it_component->first).joint_constant.position_limit.maximum);
238 log::println(
" -Relative Position from parent component : ");
240 log::println(
" -Relative Orientation from parent component : ");
263 log::println(
"---------------------------------------------");
272 component_.at(component_name).joint_constant.torque_coefficient = torque_coefficient;
327 component_.at(component_name).actuator_name = actuator_name;
334 component_.at(component_name).pose_from_world = pose_to_world;
338 log::error(
"[setComponentPoseFromWorld] Wrong name.");
346 component_.at(component_name).pose_from_world.kinematic = pose_to_world;
350 log::error(
"[setComponentKinematicPoseFromWorld] Wrong name.");
358 component_.at(component_name).pose_from_world.kinematic.position = position_to_world;
362 log::error(
"[setComponentPositionFromWorld] Wrong name.");
370 component_.at(component_name).pose_from_world.kinematic.orientation = orientation_to_wolrd;
374 log::error(
"[setComponentOrientationFromWorld] Wrong name.");
382 component_.at(component_name).pose_from_world.dynamic = dynamic_pose;
386 log::error(
"[setComponentDynamicPoseFromWorld] Wrong name.");
392 component_.at(component_name).joint_value.position = position;
397 component_.at(component_name).joint_value.velocity = velocity;
402 component_.at(component_name).joint_value.acceleration = acceleration;
407 component_.at(component_name).joint_value.effort = effort;
412 component_.at(component_name).joint_value = joint_value;
418 std::map<Name, Component>::iterator it_component;
424 component_.at(it_component->first).joint_value.position = joint_position_vector.at(index);
433 std::map<Name, Component>::iterator it_component;
439 component_.at(it_component->first).joint_value.position = joint_value_vector.at(index).position;
440 component_.at(it_component->first).joint_value.velocity = joint_value_vector.at(index).velocity;
441 component_.at(it_component->first).joint_value.acceleration = joint_value_vector.at(index).acceleration;
442 component_.at(it_component->first).joint_value.effort = joint_value_vector.at(index).effort;
451 std::map<Name, Component>::iterator it_component;
457 component_.at(it_component->first).joint_value.position = joint_position_vector.at(index);
466 std::map<Name, Component>::iterator it_component;
472 component_.at(it_component->first).joint_value = joint_value_vector.at(index);
481 std::map<Name, Component>::iterator it_component;
487 component_.at(it_component->first).joint_value.position = tool_position_vector.at(index);
496 std::map<Name, Component>::iterator it_component;
502 component_.at(it_component->first).joint_value = tool_value_vector.at(index);
579 return component_.at(component_name).actuator_name;
584 return component_.at(component_name).name.parent;
589 return component_.at(component_name).name.child;
594 return component_.at(component_name).pose_from_world;
599 return component_.at(component_name).pose_from_world.kinematic;
604 return component_.at(component_name).pose_from_world.kinematic.position;
609 return component_.at(component_name).pose_from_world.kinematic.orientation;
614 return component_.at(component_name).pose_from_world.dynamic;
619 return component_.at(component_name).relative.pose_from_parent;
624 return component_.at(component_name).relative.pose_from_parent.position;
629 return component_.at(component_name).relative.pose_from_parent.orientation;
634 return component_.at(component_name).joint_constant.id;
639 return component_.at(component_name).joint_constant.coefficient;
644 return component_.at(component_name).joint_constant.torque_coefficient;
649 return component_.at(component_name).joint_constant.axis;
654 return component_.at(component_name).joint_value.position;
659 return component_.at(component_name).joint_value.velocity;
664 return component_.at(component_name).joint_value.acceleration;
669 return component_.at(component_name).joint_value.effort;
674 return component_.at(component_name).joint_value;
679 return component_.at(component_name).relative.inertia.mass;
684 return component_.at(component_name).relative.inertia.inertia_tensor;
689 return component_.at(component_name).relative.inertia.center_of_mass;
694 std::vector<double> result_vector;
695 std::map<Name, Component>::iterator it_component;
701 result_vector.push_back(
component_.at(it_component->first).joint_value.position);
704 return result_vector;
709 std::vector<JointValue> result_vector;
710 std::map<Name, Component>::iterator it_component;
716 result_vector.push_back(
component_.at(it_component->first).joint_value);
719 return result_vector;
724 std::vector<double> result_vector;
725 std::map<Name, Component>::iterator it_component;
731 result_vector.push_back(
component_.at(it_component->first).joint_value.position);
734 return result_vector;
739 std::vector<JointValue> result_vector;
740 std::map<Name, Component>::iterator it_component;
746 result_vector.push_back(
component_.at(it_component->first).joint_value);
749 return result_vector;
754 std::vector<double> result_vector;
755 std::map<Name, Component>::iterator it_component;
761 result_vector.push_back(
component_.at(it_component->first).joint_value.position);
764 return result_vector;
770 std::vector<JointValue> result_vector;
771 std::map<Name, Component>::iterator it_component;
777 result_vector.push_back(
component_.at(it_component->first).joint_value);
780 return result_vector;
785 std::vector<uint8_t> joint_id;
786 std::map<Name, Component>::iterator it_component;
792 joint_id.push_back(
component_.at(it_component->first).joint_constant.id);
800 std::vector<uint8_t> active_joint_id;
801 std::map<Name, Component>::iterator it_component;
807 active_joint_id.push_back(
component_.at(it_component->first).joint_constant.id);
810 return active_joint_id;
816 std::vector<Name> tool_name;
817 std::map<Name, Component>::iterator it_component;
823 tool_name.push_back(it_component->first);
831 std::vector<Name> active_joint_name;
832 std::map<Name, Component>::iterator it_component;
838 active_joint_name.push_back(it_component->first);
841 return active_joint_name;
850 if(
component_.at(component_name).joint_constant.position_limit.maximum < value)
852 else if(
component_.at(component_name).joint_constant.position_limit.minimum > value)
860 if(
component_.at(component_name).component_type == component_type)
872 std::map<Name, Component>::iterator it_component;
876 if (
component_.at(it_component->first).joint_constant.id == id)
878 return it_component->first;
double getJointPosition(Name component_name)
void setComponentActuatorName(Name component_name, Name actuator_name)
void setWorldPose(Pose world_pose)
std::vector< Name > getAllToolComponentName()
std::vector< uint8_t > getAllJointID()
Name findComponentNameUsingId(int8_t id)
std::vector< JointValue > getAllJointValue()
std::map< Name, Component >::iterator getIteratorEnd()
void setWorldOrientation(Eigen::Matrix3d world_orientation)
std::vector< double > getAllJointPosition()
Pose getComponentPoseFromWorld(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())
JointValue getJointValue(Name component_name)
void setAllActiveJointPosition(std::vector< double > joint_position_vector)
void setComponentOrientationFromWorld(Name component_name, Eigen::Matrix3d orientation_to_wolrd)
std::map< Name, Component > getAllComponent()
Eigen::Matrix3d getComponentRelativeOrientationFromParent(Name component_name)
Eigen::Matrix3d getComponentOrientationFromWorld(Name component_name)
bool checkComponentType(Name component_name, ComponentType component_type)
std::vector< double > getAllActiveJointPosition()
Eigen::Vector3d getAxis(Name component_name)
double getJointAcceleration(Name component_name)
bool setEffortToValue(std::vector< JointValue > *value, std::vector< double > effort)
Eigen::Vector3d getWorldPosition()
Eigen::Vector3d getComponentRelativePositionFromParent(Name component_name)
void setAllToolPosition(std::vector< double > tool_position_vector)
void setWorldAngularVelocity(Eigen::Vector3d world_angular_velocity)
void printManipulatorSetting()
DynamicPose getWorldDynamicPose()
std::vector< uint8_t > getAllActiveJointID()
std::vector< Name > child
Name getComponentParentName(Name component_name)
void setComponent(Name component_name, Component component)
bool checkJointLimit(Name Component_name, double value)
void setAllJointPosition(std::vector< double > joint_position_vector)
void setWorldPosition(Eigen::Vector3d world_position)
void setJointAcceleration(Name name, double acceleration)
void setWorldLinearAcceleration(Eigen::Vector3d world_linear_acceleration)
Name getComponentActuatorName(Name component_name)
Eigen::Vector3d center_of_mass
void setAllActiveJointValue(std::vector< JointValue > joint_value_vector)
std::vector< Name > getAllActiveJointComponentName()
void println(STRING str, STRING color="DEFAULT")
void setJointPosition(Name name, double position)
KinematicPose getWorldKinematicPose()
Eigen::Matrix3d inertia_tensor
double getJointEffort(Name component_name)
double getCoefficient(Name component_name)
int8_t getComponentSize()
std::vector< JointValue > getAllActiveJointValue()
void setComponentPositionFromWorld(Name component_name, Eigen::Vector3d position_to_world)
KinematicPose getComponentRelativePoseFromParent(Name component_name)
DynamicPose getComponentDynamicPoseFromWorld(Name component_name)
std::map< Name, Component > component_
double getTorqueCoefficient(Name component_name)
void setTorqueCoefficient(Name component_name, double torque_coefficient)
void setComponentPoseFromWorld(Name component_name, Pose pose_to_world)
void print_vector(std::vector< T > &vec, uint8_t decimal_point=3)
void setComponentDynamicPoseFromWorld(Name component_name, DynamicPose dynamic_pose)
std::vector< Name > getComponentChildName(Name component_name)
enum robotis_manipulator::_ComponentType ComponentType
void setAllJointValue(std::vector< JointValue > joint_value_vector)
void print(STRING str, STRING color="DEFAULT")
ComponentType component_type
void setJointEffort(Name name, double effort)
void setJointVelocity(Name name, double velocity)
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)
Eigen::Matrix3d getWorldOrientation()
void setJointValue(Name name, JointValue joint_value)
void setWorldAngularAcceleration(Eigen::Vector3d world_angular_acceleration)
double getJointVelocity(Name component_name)
Eigen::Vector3d acceleration
Eigen::Vector3d getComponentPositionFromWorld(Name component_name)
double torque_coefficient
void addComponentChild(Name my_name, Name child_name)
void setComponentKinematicPoseFromWorld(Name component_name, KinematicPose pose_to_world)
double getComponentMass(Name component_name)
bool setPositionToValue(std::vector< JointValue > *value, std::vector< double > position)
KinematicPose getComponentKinematicPoseFromWorld(Name component_name)
Eigen::Vector3d getComponentCenterOfMass(Name component_name)
void setAllToolValue(std::vector< JointValue > tool_value_vector)
JointConstant joint_constant
std::map< Name, Component >::iterator getIteratorBegin()
KinematicPose pose_from_parent
Eigen::Matrix3d orientation
std::vector< double > getAllToolPosition()
Eigen::Matrix3d getComponentInertiaTensor(Name component_name)
void setWorldKinematicPose(KinematicPose world_kinematic_pose)
int8_t getId(Name component_name)
std::vector< JointValue > getAllToolValue()
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)
void print_matrix(matrix &m, uint8_t decimal_point=3)
void setWorldDynamicPose(DynamicPose world_dynamic_pose)
Component getComponent(Name component_name)
void setWorldLinearVelocity(Eigen::Vector3d world_linear_velocity)