Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enable initial position param in kinova xacros #190

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion kortex_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ endif()
find_package(ament_cmake REQUIRED)

install(
DIRECTORY arms grippers launch multiple_robots robots rviz
DIRECTORY arms grippers launch multiple_robots robots rviz config
DESTINATION share/${PROJECT_NAME}
)

Expand Down
8 changes: 8 additions & 0 deletions kortex_description/config/initial_positions.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
# NOTE: Used for both 6 and 7 dof bots. The joint_7 value will be unused for 6 dof bots
joint_1: 0.0
joint_2: 0.0
joint_3: 0.0
joint_4: 0.0
joint_5: 0.0
joint_6: 0.0
joint_7: 0.0
7 changes: 6 additions & 1 deletion kortex_description/robots/gen3.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,10 @@
<xacro:arg name="use_external_cable" default="false" />

<xacro:include filename="$(find kortex_description)/robots/kortex_robot.xacro" />
<!-- initial position for simulations (Mock Hardware, Gazebo, Ignition) -->
<xacro:arg name="initial_positions_file" default="$(find kortex_description)/config/initial_positions.yaml"/>
<!-- convert to property to use substitution in function -->
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>
<link name="world" />
<xacro:load_robot
parent="world"
Expand All @@ -51,7 +55,8 @@
sim_gazebo="$(arg sim_gazebo)"
sim_ignition="$(arg sim_ignition)"
sim_isaac="$(arg sim_isaac)"
use_external_cable="$(arg use_external_cable)" >
use_external_cable="$(arg use_external_cable)"
initial_positions="${xacro.load_yaml(initial_positions_file)}" >
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
</xacro:load_robot>

Expand Down
9 changes: 8 additions & 1 deletion kortex_description/robots/kinova.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,12 @@
<!-- import main macro -->
<xacro:include filename="$(find kortex_description)/robots/kortex_robot.xacro" />

<!-- initial position for simulations (Mock Hardware, Gazebo, Ignition) -->
<xacro:arg name="initial_positions_file" default="$(find kortex_description)/config/initial_positions.yaml"/>

<!-- convert to property to use substitution in function -->
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

<!-- create link fixed to the "world" -->
<link name="world" />

Expand All @@ -61,7 +67,8 @@
fake_sensor_commands="$(arg fake_sensor_commands)"
sim_gazebo="$(arg sim_gazebo)"
sim_ignition="$(arg sim_ignition)"
sim_isaac="$(arg sim_isaac)" >
sim_isaac="$(arg sim_isaac)"
initial_positions="${xacro.load_yaml(initial_positions_file)}" >
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
</xacro:load_robot>

Expand Down
4 changes: 3 additions & 1 deletion kortex_description/robots/kortex_robot.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
isaac_joint_commands:=/isaac_joint_commands
isaac_joint_states:=/isaac_joint_states
use_external_cable:=false
initial_positions:=${dict(joint_1=0.0,joint_2=0.0,joint_3=0.0,joint_4=0.0,joint_5=0.0,joint_6=0.0,joint_7=0.0)}
dyackzan marked this conversation as resolved.
Show resolved Hide resolved
gripper_max_velocity:=100.0
gripper_max_force:=100.0">

Expand Down Expand Up @@ -57,7 +58,8 @@
gripper_joint_name="${gripper_joint_name}"
gripper_max_velocity="${gripper_max_velocity}"
gripper_max_force="${gripper_max_force}"
use_external_cable="${use_external_cable}">
use_external_cable="${use_external_cable}"
initial_positions="${initial_positions}">
<xacro:insert_block name="origin" />
</xacro:load_arm>

Expand Down
Loading