Skip to content

Commit

Permalink
Canadarm moveit setup (space-ros#12)
Browse files Browse the repository at this point in the history
* paths

Signed-off-by: Dharini Dutia <[email protected]>

* moveit framework

Signed-off-by: Dharini Dutia <[email protected]>

* reverting launch

Signed-off-by: Dharini Dutia <[email protected]>

* moveit config

Signed-off-by: Dharini Dutia <[email protected]>

* fixing robot name

Signed-off-by: Dharini Dutia <[email protected]>

* fixing warnings

Signed-off-by: Dharini Dutia <[email protected]>

---------

Signed-off-by: Dharini Dutia <[email protected]>
  • Loading branch information
quarkytale authored Feb 28, 2023
1 parent f0906cc commit b07b796
Show file tree
Hide file tree
Showing 24 changed files with 509 additions and 4 deletions.
51 changes: 51 additions & 0 deletions canadarm/nodes/hello_moveit.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#include <memory>

#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.h>

int main(int argc, char* argv[])
{
// Initialize ROS and create the Node
rclcpp::init(argc, argv);
auto const node = std::make_shared<rclcpp::Node>(
"hello_moveit", rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));

// Create a ROS logger
auto const logger = rclcpp::get_logger("hello_moveit");

// Create the MoveIt MoveGroup Interface
using moveit::planning_interface::MoveGroupInterface;
auto move_group_interface = MoveGroupInterface(node, "canadarm");

// Set a target Pose
auto const target_pose = [] {
geometry_msgs::msg::Pose msg;
msg.orientation.w = 1.0;
msg.position.x = 0.28;
msg.position.y = -0.2;
msg.position.z = 0.5;
return msg;
}();
move_group_interface.setPoseTarget(target_pose);

// Create a plan to that target pose
auto const [success, plan] = [&move_group_interface] {
moveit::planning_interface::MoveGroupInterface::Plan msg;
auto const ok = static_cast<bool>(move_group_interface.plan(msg));
return std::make_pair(ok, msg);
}();

// Execute the plan
if (success)
{
move_group_interface.execute(plan);
}
else
{
RCLCPP_ERROR(logger, "Planning failed!");
}

// Shutdown ROS
rclcpp::shutdown();
return 0;
}
6 changes: 3 additions & 3 deletions canadarm/worlds/simple.world
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
<visual name='visual'>
<geometry>
<mesh>
<uri>package://simulation/canadarm/meshes/earth.dae</uri>
<uri>/home/spaceros-user/demos_ws/install/simulation/share/simulation/models/canadarm/meshes/earth.dae</uri>
<scale>3 3 3</scale>
</mesh>
</geometry>
Expand Down Expand Up @@ -77,7 +77,7 @@
<visual name='visual'>
<geometry>
<mesh>
<uri>package://simulation/canadarm/meshes/iss.dae</uri>
<uri>/home/spaceros-user/demos_ws/install/simulation/share/simulation/models/canadarm/meshes/iss.dae</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
Expand All @@ -92,4 +92,4 @@
</link>
</model>
</world>
</sdf>
</sdf>
27 changes: 27 additions & 0 deletions 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 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(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})
70 changes: 70 additions & 0 deletions canadarm_moveit_config/config/SSRMS_Canadarm2.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="SSRMS_Canadarm2_ros2_control" params="name initial_positions_file">
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>

<ros2_control name="${name}" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<plugin>mock_components/GenericSystem</plugin>
</hardware>
<joint name="Base_Joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['Base_Joint']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="Shoulder_Roll">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['Shoulder_Roll']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="Shoulder_Yaw">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['Shoulder_Yaw']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="Elbow_Pitch">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['Elbow_Pitch']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="Wrist_Pitch">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['Wrist_Pitch']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="Wrist_Yaw">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['Wrist_Yaw']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<joint name="Wrist_Roll">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['Wrist_Roll']}</param>
</state_interface>
<state_interface name="velocity"/>
</joint>

</ros2_control>
</xacro:macro>
</robot>
56 changes: 56 additions & 0 deletions canadarm_moveit_config/config/SSRMS_Canadarm2.srdf
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>
14 changes: 14 additions & 0 deletions canadarm_moveit_config/config/SSRMS_Canadarm2.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="SSRMS_Canadarm2">
<xacro:arg name="initial_positions_file" default="initial_positions.yaml" />

<!-- Import SSRMS_Canadarm2 urdf file -->
<xacro:include filename="$(find simulation)/models/canadarm/urdf/SSRMS_Canadarm2.urdf" />

<!-- Import control_xacro -->
<xacro:include filename="SSRMS_Canadarm2.ros2_control.xacro" />


<xacro:SSRMS_Canadarm2_ros2_control name="FakeSystem" initial_positions_file="$(arg initial_positions_file)"/>

</robot>
10 changes: 10 additions & 0 deletions canadarm_moveit_config/config/initial_positions.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
# Default initial positions for SSRMS_Canadarm2's ros2_control fake system

initial_positions:
Base_Joint: 0
Elbow_Pitch: 0
Shoulder_Roll: 0
Shoulder_Yaw: 0
Wrist_Pitch: 0
Wrist_Roll: 0
Wrist_Yaw: 0
45 changes: 45 additions & 0 deletions canadarm_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed

# For beginners, we downscale velocity and acceleration limits.
# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
default_velocity_scaling_factor: 0.1
default_acceleration_scaling_factor: 0.1

# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
joint_limits:
Base_Joint:
has_velocity_limits: true
max_velocity: 0.069813200000000006
has_acceleration_limits: false
max_acceleration: 0
Elbow_Pitch:
has_velocity_limits: true
max_velocity: 0.069813200000000006
has_acceleration_limits: false
max_acceleration: 0
Shoulder_Roll:
has_velocity_limits: true
max_velocity: 0.069813200000000006
has_acceleration_limits: false
max_acceleration: 0
Shoulder_Yaw:
has_velocity_limits: true
max_velocity: 0.069813200000000006
has_acceleration_limits: false
max_acceleration: 0
Wrist_Pitch:
has_velocity_limits: true
max_velocity: 0.069813200000000006
has_acceleration_limits: false
max_acceleration: 0
Wrist_Roll:
has_velocity_limits: true
max_velocity: 0.069813200000000006
has_acceleration_limits: false
max_acceleration: 0
Wrist_Yaw:
has_velocity_limits: true
max_velocity: 0.069813200000000006
has_acceleration_limits: false
max_acceleration: 0
8 changes: 8 additions & 0 deletions canadarm_moveit_config/config/kinematics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
canadarm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001
canadarm_planning_group:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001
51 changes: 51 additions & 0 deletions canadarm_moveit_config/config/moveit.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
Panels:
- Class: rviz_common/Displays
Name: Displays
Property Tree Widget:
Expanded:
- /MotionPlanning1
- Class: rviz_common/Help
Name: Help
- Class: rviz_common/Views
Name: Views
Visualization Manager:
Displays:
- Class: rviz_default_plugins/Grid
Name: Grid
Value: true
- Class: moveit_rviz_plugin/MotionPlanning
Name: MotionPlanning
Planned Path:
Loop Animation: true
State Display Time: 0.05 s
Trajectory Topic: display_planned_path
Planning Scene Topic: monitored_planning_scene
Robot Description: robot_description
Scene Geometry:
Scene Alpha: 1
Scene Robot:
Robot Alpha: 0.5
Value: true
Global Options:
Fixed Frame: world
Tools:
- Class: rviz_default_plugins/Interact
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 2.0
Focal Point:
X: -0.1
Y: 0.25
Z: 0.30
Name: Current View
Pitch: 0.5
Target Frame: world
Yaw: -0.623
Window Geometry:
Height: 975
QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Width: 1200
Loading

0 comments on commit b07b796

Please sign in to comment.