Robot.Links (dpp v0.1.1)
Provide functions that import robot links
Link to this section Summary
Functions
Add meshes and transform info to robot model by using the name of the linkParameters
- robot_model: robot model used to store mesh and tranform information
- geometries: List of geometries to store geometry data
- names: names of the gerometries
- link: robto link
- name: name of the geometry
- joint_value: angle of the joint in radExamples
geometries = File.read!("geometries.txt") |> :erlang.binary_to_term
link_base = File.read!("link_base.txt") |> :erlang.binary_to_term
link_1 = File.read!("link_1.txt") |> :erlang.binary_to_term
link_2 = File.read!("link_2.txt") |> :erlang.binary_to_term
link_3 = File.read!("link_3.txt") |> :erlang.binary_to_term
link_4 = File.read!("link_4.txt") |> :erlang.binary_to_term
link_5 = File.read!("link_5.txt") |> :erlang.binary_to_term
link_6 = File.read!("link_6.txt") |> :erlang.binary_to_term
robot_model = %{points: [], indices: [], translates: [], rotates: []}
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_base, 'gkmodel0_base_link_geom0', 0.0)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_1, 'gkmodel0_link_1_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_2, 'gkmodel0_link_2_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_3, 'gkmodel0_link_3_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_4, 'gkmodel0_link_4_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_5, 'gkmodel0_link_5_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_6, 'gkmodel0_link_6_geom0', :math.pi/6)Perform frame transformation.Parameters
- old_trans: the first translation vector
- old_rots: the first rotation axis+angle
- new_trans: the secord tranlation vector
- new_rots: the secord rotation axis+angle
- joint_vector: the joint rotaion axis+angleConvert List of Char to a List of FLoat.Parameters
- charlist: Charlist Example: '1 2 3'Examples
iex(6)> charlist_to_flist('1 2 3')
[1.0, 2.0, 3.0]Convert string list to float list in frame, and add name to frameParameters
- xmlresult: frame
- name: link node path in xmlExamples
translates_path = %SweetXpath{path: './node[@name="'++link_name++'"]/translate/text()', is_list: true}
rotate_axis_sid_path = %SweetXpath{path: './node[@name="'++link_name++'"]/rotate/@sid'}
rotates_path = %SweetXpath{path: './node[@name="'++link_name++'"]/rotate/text()', is_list: true}
result = xmldoc |> xpath(
link_path,
translates: instance_geometry_path = translates_path,
rotate_axis_sid: rotate_axis_sid_path,
rotates: rotates_path
)
frame = convert_to_frame(result, link_name)Get base frame information in a Map
TODO: develop information model for robot.Parameters
- xmldoc: xml file readedExamples
result = get_base_frame(xmldoc)Get base link information in a Map
TODO: develop information model for robot.Parameters
- xmldoc: xml file readedExamples
result = get_base_link(xmldoc)Get link information and return a Map based on name input
TODO: develop information model for robot.Parameters
- xmldoc: xml file readed
- link_path: link node path in xml
- link_name: link name Examples
link_name = 'link_6'
link_6_path = get_link_path(link_name)
result = get_link(xmldoc, link_6_path, link_name)Get link_1 information and put it in a Map
TODO: develop information model for robot.Parameters
- xmldoc: xml file readedExamples
iex> get_link_1(xmldoc)
%{frame:
%{frames:
[%{rotate: [1.0, 0.0, 0.0, 0.0], translate: [0.0, 0.0, 0.0]},
%{rotate: [1.0, 0.0, 0.0, 0.0], translate: [0.0, 0.0, 0.227]},
%{rotate: [1.0, 0.0, 0.0, 0.0], translate: [0.0, 0.0, 0.0]}],
name: 'link_1',
rotate_axis: [0.0, 0.0, 1.0, 0.0],
rotate_axis_sid: 'node_joint_1_axis0'},
instance_geometry: ['#gkmodel0_link_1_geom0'],
link_name: 'link_1',
linked_links: ['link_2', 'link_cylinder']}TODO: merge to get_link_n, after development of information model
TODO: merge to get_link_n, after development of information model
TODO: merge to get_link_n, after development of information model
TODO: merge to get_link_n, after development of information model
TODO: merge to get_link_n, after development of information model
Get link frames information and return a Map based on name input
TODO: develop information model for robot.Parameters
- xmldoc: xml file readed
- link_path: link node path in xml
- link_name: link name Examples
link_name = 'link_6'
link_6_path = get_link_path(link_name)
result = get_link(xmldoc, link_6_path, link_name)Get link path based on link name
TODO: develop information model for robot.Parameters
- link: name of linkExamples
link_name = 'link_6'
link_6_path = get_link_path(link_name)Generate Robot mesh based on jointsParameters
- joints: Joints inputExamples
joints = %Robot.Joints{joint1: :math.pi/6, joint2: :math.pi/6, joint3: :math.pi/6, joint4: :math.pi/6, joint5: :math.pi/6, joint6: :math.pi/6}
robot_model = get_robot_model_based_on_joint_value(joints)
points = robot_model.points
indices = robot_model.indices
translates = robot_model.translates
rotates = robot_model.rotates
draw(points,indices,translates,rotates)TODO
Link to this section Functions
Link to this function
add_link_to_robot_model_by_name(robot_model, geometries, names, link, name, joint_value)
Specs
add_link_to_robot_model_by_name(
%{points: List, indices: List, translates: List, rotates: List},
List,
List,
%{
link_name: Charlist,
instance_geometry: List,
frame: %{
name: Charlist,
rotate_axis_sid: Charlist,
frames: List,
rotate_axis: List
},
linked_links: List
},
Charlist,
Float
) :: Rbot.Mesh
Add meshes and transform info to robot model by using the name of the linkParameters
- robot_model: robot model used to store mesh and tranform information
- geometries: List of geometries to store geometry data
- names: names of the gerometries
- link: robto link
- name: name of the geometry
- joint_value: angle of the joint in radExamples
geometries = File.read!("geometries.txt") |> :erlang.binary_to_term
link_base = File.read!("link_base.txt") |> :erlang.binary_to_term
link_1 = File.read!("link_1.txt") |> :erlang.binary_to_term
link_2 = File.read!("link_2.txt") |> :erlang.binary_to_term
link_3 = File.read!("link_3.txt") |> :erlang.binary_to_term
link_4 = File.read!("link_4.txt") |> :erlang.binary_to_term
link_5 = File.read!("link_5.txt") |> :erlang.binary_to_term
link_6 = File.read!("link_6.txt") |> :erlang.binary_to_term
robot_model = %{points: [], indices: [], translates: [], rotates: []}
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_base, 'gkmodel0_base_link_geom0', 0.0)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_1, 'gkmodel0_link_1_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_2, 'gkmodel0_link_2_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_3, 'gkmodel0_link_3_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_4, 'gkmodel0_link_4_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_5, 'gkmodel0_link_5_geom0', :math.pi/6)
robot_model = add_link_to_robot_model_by_name(robot_model, geometries, names, link_6, 'gkmodel0_link_6_geom0', :math.pi/6)
Link to this function
apply_joint(old_trans, old_rots, new_trans, new_rots, joint_vector)
Specs
apply_joint(List, List, List, List, List) :: List
Perform frame transformation.Parameters
- old_trans: the first translation vector
- old_rots: the first rotation axis+angle
- new_trans: the secord tranlation vector
- new_rots: the secord rotation axis+angle
- joint_vector: the joint rotaion axis+angle
Link to this function
charlist_to_flist(charlist)
Specs
charlist_to_flist(Charlist) :: List
Convert List of Char to a List of FLoat.Parameters
- charlist: Charlist Example: '1 2 3'Examples
iex(6)> charlist_to_flist('1 2 3')
[1.0, 2.0, 3.0]
Link to this function
convert_to_frame(xmlresult, name)
Specs
convert_to_frame(binary(), Charlist) :: Robot.Frame
Convert string list to float list in frame, and add name to frameParameters
- xmlresult: frame
- name: link node path in xmlExamples
translates_path = %SweetXpath{path: './node[@name="'++link_name++'"]/translate/text()', is_list: true}
rotate_axis_sid_path = %SweetXpath{path: './node[@name="'++link_name++'"]/rotate/@sid'}
rotates_path = %SweetXpath{path: './node[@name="'++link_name++'"]/rotate/text()', is_list: true}
result = xmldoc |> xpath(
link_path,
translates: instance_geometry_path = translates_path,
rotate_axis_sid: rotate_axis_sid_path,
rotates: rotates_path
)
frame = convert_to_frame(result, link_name)
Link to this function
get_base_frame(xmldoc)
Specs
get_base_frame(binary()) :: Robot.Frame
Get base frame information in a Map
TODO: develop information model for robot.Parameters
- xmldoc: xml file readedExamples
result = get_base_frame(xmldoc)
Link to this function
get_base_link(xmldoc)
Specs
get_base_link(binary()) :: Robot.Link
Get base link information in a Map
TODO: develop information model for robot.Parameters
- xmldoc: xml file readedExamples
result = get_base_link(xmldoc)
Link to this function
get_link(xmldoc, link_path, link_name)
Specs
get_link( binary(), %SweetXpath{ cast_to: term(), is_keyword: term(), is_list: term(), is_optional: term(), is_value: term(), namespaces: term(), path: term(), transform_fun: term() }, Charlist ) :: %{link_name: Charlist, instance_geometry: List, linked_links: List}
Get link information and return a Map based on name input
TODO: develop information model for robot.Parameters
- xmldoc: xml file readed
- link_path: link node path in xml
- link_name: link name Examples
link_name = 'link_6'
link_6_path = get_link_path(link_name)
result = get_link(xmldoc, link_6_path, link_name)
Link to this function
get_link_1(xmldoc)
Specs
get_link_1(binary()) :: Robot.Link
Get link_1 information and put it in a Map
TODO: develop information model for robot.Parameters
- xmldoc: xml file readedExamples
iex> get_link_1(xmldoc)
%{frame:
%{frames:
[%{rotate: [1.0, 0.0, 0.0, 0.0], translate: [0.0, 0.0, 0.0]},
%{rotate: [1.0, 0.0, 0.0, 0.0], translate: [0.0, 0.0, 0.227]},
%{rotate: [1.0, 0.0, 0.0, 0.0], translate: [0.0, 0.0, 0.0]}],
name: 'link_1',
rotate_axis: [0.0, 0.0, 1.0, 0.0],
rotate_axis_sid: 'node_joint_1_axis0'},
instance_geometry: ['#gkmodel0_link_1_geom0'],
link_name: 'link_1',
linked_links: ['link_2', 'link_cylinder']}
Link to this function
get_link_2(xmldoc)
TODO: merge to get_link_n, after development of information model
Link to this function
get_link_3(xmldoc)
TODO: merge to get_link_n, after development of information model
Link to this function
get_link_4(xmldoc)
TODO: merge to get_link_n, after development of information model
Link to this function
get_link_5(xmldoc)
TODO: merge to get_link_n, after development of information model
Link to this function
get_link_6(xmldoc)
TODO: merge to get_link_n, after development of information model
Link to this function
get_link_frame(xmldoc, link_path, link_name)
Specs
get_link_frame( binary(), %SweetXpath{ cast_to: term(), is_keyword: term(), is_list: term(), is_optional: term(), is_value: term(), namespaces: term(), path: term(), transform_fun: term() }, Charlist ) :: Robot.Frame
Get link frames information and return a Map based on name input
TODO: develop information model for robot.Parameters
- xmldoc: xml file readed
- link_path: link node path in xml
- link_name: link name Examples
link_name = 'link_6'
link_6_path = get_link_path(link_name)
result = get_link(xmldoc, link_6_path, link_name)
Link to this function
get_link_path(link)
Specs
get_link_path(Charlist) :: %SweetXpath{
cast_to: term(),
is_keyword: term(),
is_list: term(),
is_optional: term(),
is_value: term(),
namespaces: term(),
path: term(),
transform_fun: term()
}
Get link path based on link name
TODO: develop information model for robot.Parameters
- link: name of linkExamples
link_name = 'link_6'
link_6_path = get_link_path(link_name)
Link to this function
get_robot_model_based_on_joint_value(joints)
Specs
get_robot_model_based_on_joint_value(Robot.Joints) :: Robot.Mesh
Generate Robot mesh based on jointsParameters
- joints: Joints inputExamples
joints = %Robot.Joints{joint1: :math.pi/6, joint2: :math.pi/6, joint3: :math.pi/6, joint4: :math.pi/6, joint5: :math.pi/6, joint6: :math.pi/6}
robot_model = get_robot_model_based_on_joint_value(joints)
points = robot_model.points
indices = robot_model.indices
translates = robot_model.translates
rotates = robot_model.rotates
draw(points,indices,translates,rotates)
Link to this function
get_tool_frame()
TODO