The Arm Commander API References
arm_commander.commander_moveit module
arm_commander.states module
arm_commander.tools.moveit_tools module
- arm_commander.tools.moveit_tools.create_code_to_string_map(the_class, keep_full_uppercase: bool = True, omit_begin_underscore: bool = True) dict
- A utility for converting the uppercase variables of a class into a string map for conversion from variable values to variable names.
It is applied on non-Enum class and provides a similar functionality of printing out the name of an Enum value
- Parameters:
the_class (A Python class definition) – The class that contains the variables
keep_full_uppercase (bool, optional) – Extracts only the variables in full uppercase, defaults to True
omit_begin_underscore (bool, optional) – Omits the variables beginning with an underscore, defaults to True
- Returns:
the string map (variable value, variable names)
- Return type:
dict
- arm_commander.tools.moveit_tools.create_path_joint_constraint(joint_name: str, min_value: float, max_value: float) moveit_msgs.msg.JointConstraint
Return a populated joint constraint
- Parameters:
joint_name (str) – the name of the joint subject to the constraint
min_value (float) – the allowable minimum joint value
max_value (float) – the allowable maximum joint value
- Returns:
The populated joint constraint
- Return type:
JointConstraint
- arm_commander.tools.moveit_tools.create_path_orientation_constraint(link_name: str, current_pose: geometry_msgs.msg.PoseStamped, x_axis: float, y_axis: float, z_axis: float) moveit_msgs.msg.OrientationConstraint
Return a populated orientation constraint
- Parameters:
link_name (str) – the name of the robot_link subject to the constraint
current_pose (PoseStamped) – The current pose of the link that is used as the reference
x_axis (float) – The absolute tolerance in the x axis
y_axis (float) – The absolute tolerance in the y axis
z_axis (float) – The absolute tolerance in the z axis
- Returns:
The populated orientation constraint
- Return type:
OrientationConstraint
- arm_commander.tools.moveit_tools.create_position_constraint(link_name: str, reference_frame: str, xyz: list, dimensions: list) moveit_msgs.msg.PositionConstraint
return a populated PositionContraint
- Parameters:
link_name (str) – the name of the robot_link subject to the constraint
reference_frame (str) – the reference frame defining the orientation of the xyz and dimensions
xyz (list) – the centroid of the box that defines the position constraint
dimensions (list) – the dimension of the box that defines the constraint
- Returns:
the populated PositionContraint
- Return type:
PositionConstraint
- arm_commander.tools.moveit_tools.create_position_constraint_from_bbox(link_name: str, reference_frame: str, bbox: list) moveit_msgs.msg.PositionConstraint
return a populated PositionContraint
- Parameters:
link_name (str) – the name of the robot_link subject to the constraint
reference_frame (str) – the reference frame defining the orientation of the xyz and dimensions
bbox (a list of 6 numbers (min_x, min_y, min_z, max_x, max_y, max_z)) – the bounding box that defines the position constraint
- Returns:
the populated PositionContraint
- Return type:
PositionConstraint
- arm_commander.tools.moveit_tools.create_position_constraint_on_link_orientation(link_name: str, current_pose: geometry_msgs.msg.PoseStamped, dimensions_in_pose_orientation: list) moveit_msgs.msg.PositionConstraint
return a populated PositionContraint
- Parameters:
link_name (str) – the name of the robot_link subject to the constraint
current_pose (PoseStamped) – the reference pose based on which the dimension in the position constraint is defined, with the reference pose at the centroid
dimensions_in_pose_orientation (list) – the dimension of the box that defines the position constraint
- Returns:
the populated PositionContraint
- Return type:
PositionConstraint
arm_commander.tools.pose_tools module
- arm_commander.tools.pose_tools.list_to_pose(pose) geometry_msgs.msg.Pose
Convert a pose in xyzrpy or xyzq format to Pose
- Parameters:
pose – s pose in a list format of xyzrpy or xyzq
- Returns:
a Pose object with the same pose
- arm_commander.tools.pose_tools.list_to_pose_stamped(pose, frame) geometry_msgs.msg.PoseStamped
Convert a pose in xyzrpy or xyzq format in a reference frame to PoseStamped
- Parameters:
pose – a pose in a list format of xyzrpy or xyzq
frame – the reference frame of type str
- Returns:
a Pose object with the same pose
- arm_commander.tools.pose_tools.list_to_xyzq(pose) list
Convert a pose in xyzrpy or xyzq format to xyzq format
- Parameters:
pose – a pose in a list format of xyzrpy or xyzq
- Returns:
a list of the format xyzqqqq with the same pose
- arm_commander.tools.pose_tools.list_to_xyzrpy(pose) list
Convert a pose in xyzrpy or xyzq format to xyzrpy format
- Parameters:
pose – a pose in a list format of xyzrpy or xyzq
- Returns:
a list of the format xyzrpy with the same pose
- arm_commander.tools.pose_tools.pose_stamped_to_point_stamped(pose_stamped: geometry_msgs.msg.PoseStamped) geometry_msgs.msg.PointStamped
Convert a PoseStamped object into PointStamped object
- arm_commander.tools.pose_tools.pose_stamped_to_transform_stamped(pose_stamped: geometry_msgs.msg.PoseStamped, reference_frame: str) geometry_msgs.msg.TransformStamped
Convert a PoseStamped object into TransformStamped object
- arm_commander.tools.pose_tools.pose_to_xyzq(pose) list
Convert a pose in Pose or PoseStamped format to xyzq format
- Parameters:
pose – the pose of type Pose or PoseStamped
- Returns:
a list of the format xyzqqqq with the same pose
- arm_commander.tools.pose_tools.pose_to_xyzrpy(pose) list
Convert a pose in Pose or PoseStamped format into xyzrpy format
- Parameters:
pose – the pose of type Pose or PoseStamped
- Returns:
a list of the format xyzrpy with the same pose
- arm_commander.tools.pose_tools.same_joint_values_with_tolerence(joint_values_1: list, joint_values_2: list, tolerance: float = 0.1) bool
Test if the two sets of joint values are the same
- Parameters:
joint_values_1 (list) – the first set of joint_values
joint_values_2 (list) – the second set of joint values
tolerance (float) – the absolute tolerance for the comparison
- Returns:
True if the two sets of joint values are deemed the same
- Return type:
bool
- arm_commander.tools.pose_tools.same_pose_with_tolerence(pose_1, pose_2, tolerance: float = 0.01) bool
test if two poses are the same within a tolerance of each other.
- Parameters:
goal (A list of floats or a Pose) – A pose
actual (A list of floats or a Pose) – another pose
tolerance (float) – the absolute tolerance for the comparison
- Returns:
True if the goal and actual are the same
- Return type:
bool
- arm_commander.tools.pose_tools.same_rpy_with_tolerence(rpy_1: list, rpy_2: list, tolerance: float = 0.01) bool
test if two euler’s angles are the same
- Parameters:
rpy_1 (list) – the first orientation in euler’s angle
rpy_2 (list) – the second orientation in euler’s angle
tolerance (float) – the absolute tolerance for the comparison
- Returns:
True if the two orientations are deemed the same
- Return type:
bool
- arm_commander.tools.pose_tools.same_xyz_with_tolerence(xyz_1: list, xyz_2: list, tolerance: float = 0.01) bool
test if two positions are the same
- Parameters:
xyz_1 (list) – the first position in xyz
xyz_2 (list) – the second position in xyz
tolerance (float) – the absolute tolerance for the comparison
- Returns:
True if the two orientations are deemed the same
- Return type:
bool
- arm_commander.tools.pose_tools.transform_to_pose_stamped(transform: geometry_msgs.msg.TransformStamped) geometry_msgs.msg.PoseStamped
Convert a TransformStamped object into PoseStamped object