Skip to content

Commit

Permalink
NASA_Challenge_[@xfiderek] Add canadarm2 moveit config for trick demo (
Browse files Browse the repository at this point in the history
…space-ros#42).

Adds moveit config with ros2 controllers configuration for the end to end demo.
  • Loading branch information
xfiderek committed Sep 6, 2024
1 parent 399d664 commit d4d8acb
Show file tree
Hide file tree
Showing 22 changed files with 1,357 additions and 0 deletions.
27 changes: 27 additions & 0 deletions ros_trick/ros_src/trick_canadarm_moveit_config/.setup_assistant
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
moveit_setup_assistant_config:
urdf:
package: simulation
relative_path: models/canadarm/urdf/SSRMS_Canadarm2.urdf
srdf:
relative_path: config/SSRMS_Canadarm2.srdf
package_settings:
author_name: Dharini Dutia
author_email: [email protected]
generated_timestamp: 1672757808
control_xacro:
command:
- position
- velocity
state:
- position
- velocity
modified_urdf:
xacros:
- control_xacro
control_xacro:
command:
- position
- velocity
state:
- position
- velocity
11 changes: 11 additions & 0 deletions ros_trick/ros_src/trick_canadarm_moveit_config/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
cmake_minimum_required(VERSION 3.22)
project(trick_canadarm_moveit_config)

find_package(ament_cmake REQUIRED)

ament_package()

install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}
PATTERN "setup_assistant.launch" EXCLUDE)
install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME})
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="SSRMS_Canadarm2_ros2_control" params="name">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>trick_ros2_control/TrickSystem</plugin>
<param name="trick_variable_server_host">localhost</param>
<param name="trick_variable_server_port">49765</param>
<param name="trick_variable_cycle_rate">100.0</param>
</hardware>

<joint name="Base_Joint">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="effort"/>
<param name="state_interface/position/trick_variable_name">CanadarmManip.manip.q[0]</param>
<param name="state_interface/velocity/trick_variable_name">CanadarmManip.manip.q_dot[0]</param>
<param name="state_interface/acceleration/trick_variable_name">CanadarmManip.manip.q_dotdot[0]</param>
<param name="command_interface/effort/trick_variable_name">CanadarmManip.manip.input_torque[0]</param>
</joint>

<joint name="Shoulder_Roll">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="effort"/>
<param name="state_interface/position/trick_variable_name">CanadarmManip.manip.q[1]</param>
<param name="state_interface/velocity/trick_variable_name">CanadarmManip.manip.q_dot[1]</param>
<param name="state_interface/acceleration/trick_variable_name">CanadarmManip.manip.q_dotdot[1]</param>
<param name="command_interface/effort/trick_variable_name">CanadarmManip.manip.input_torque[1]</param>
</joint>

<joint name="Shoulder_Yaw">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="effort"/>
<param name="state_interface/position/trick_variable_name">CanadarmManip.manip.q[2]</param>
<param name="state_interface/velocity/trick_variable_name">CanadarmManip.manip.q_dot[2]</param>
<param name="state_interface/acceleration/trick_variable_name">CanadarmManip.manip.q_dotdot[2]</param>
<param name="command_interface/effort/trick_variable_name">CanadarmManip.manip.input_torque[2]</param>
</joint>

<joint name="Elbow_Pitch">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="effort"/>
<param name="state_interface/position/trick_variable_name">CanadarmManip.manip.q[3]</param>
<param name="state_interface/velocity/trick_variable_name">CanadarmManip.manip.q_dot[3]</param>
<param name="state_interface/acceleration/trick_variable_name">CanadarmManip.manip.q_dotdot[3]</param>
<param name="command_interface/effort/trick_variable_name">CanadarmManip.manip.input_torque[3]</param>
</joint>

<joint name="Wrist_Pitch">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="effort"/>
<param name="state_interface/position/trick_variable_name">CanadarmManip.manip.q[4]</param>
<param name="state_interface/velocity/trick_variable_name">CanadarmManip.manip.q_dot[4]</param>
<param name="state_interface/acceleration/trick_variable_name">CanadarmManip.manip.q_dotdot[4]</param>
<param name="command_interface/effort/trick_variable_name">CanadarmManip.manip.input_torque[4]</param>
</joint>

<joint name="Wrist_Yaw">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="effort"/>
<param name="state_interface/position/trick_variable_name">CanadarmManip.manip.q[5]</param>
<param name="state_interface/velocity/trick_variable_name">CanadarmManip.manip.q_dot[5]</param>
<param name="state_interface/acceleration/trick_variable_name">CanadarmManip.manip.q_dotdot[5]</param>
<param name="command_interface/effort/trick_variable_name">CanadarmManip.manip.input_torque[5]</param>
</joint>

<joint name="Wrist_Roll">
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<command_interface name="effort"/>
<param name="state_interface/position/trick_variable_name">CanadarmManip.manip.q[6]</param>
<param name="state_interface/velocity/trick_variable_name">CanadarmManip.manip.q_dot[6]</param>
<param name="state_interface/acceleration/trick_variable_name">CanadarmManip.manip.q_dotdot[6]</param>
<param name="command_interface/effort/trick_variable_name">CanadarmManip.manip.input_torque[6]</param>
</joint>
</ros2_control>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot name="SSRMS_Canadarm2">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="canadarm">
<link name="world"/>
<link name="Base_SSRMS"/>
<link name="B1"/>
<link name="B2"/>
<link name="B3"/>
<link name="B4"/>
<link name="B5"/>
<link name="B6"/>
<link name="EE_SSRMS"/>
<joint name="world_joint"/>
<joint name="world_joint"/>
<joint name="Base_Joint"/>
<joint name="Shoulder_Roll"/>
<joint name="Shoulder_Yaw"/>
<joint name="Elbow_Pitch"/>
<joint name="Wrist_Pitch"/>
<joint name="Wrist_Yaw"/>
<joint name="Wrist_Roll"/>
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="home" group="canadarm">
<joint name="Base_Joint" value="0"/>
<joint name="Elbow_Pitch" value="0"/>
<joint name="Shoulder_Roll" value="0"/>
<joint name="Shoulder_Yaw" value="0"/>
<joint name="Wrist_Pitch" value="0"/>
<joint name="Wrist_Roll" value="0"/>
<joint name="Wrist_Yaw" value="0"/>
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="end_effector" parent_link="EE_SSRMS" group="canadarm"/>
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="world_joint" type="fixed" parent_frame="world" child_link="Base_SSRMS"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="B1" link2="B2" reason="User"/>
<disable_collisions link1="B1" link2="Base_SSRMS" reason="User"/>
<disable_collisions link1="B1" link2="EE_SSRMS" reason="User"/>
<disable_collisions link1="B2" link2="B3" reason="User"/>
<disable_collisions link1="B3" link2="B4" reason="User"/>
<disable_collisions link1="B4" link2="B5" reason="User"/>
<disable_collisions link1="B5" link2="B6" reason="User"/>
<disable_collisions link1="B6" link2="EE_SSRMS" reason="User"/>
<disable_collisions link1="Base_SSRMS" link2="EE_SSRMS" reason="User"/>
</robot>
Loading

0 comments on commit d4d8acb

Please sign in to comment.