A modular ROS 2 package designed for motion planning and control of a UR5 robotic arm, supporting joint-space, Cartesian-space, and sinusoidal trajectory generation. Compatible with Gazebo simulation and RViz visualization tools.
This repository provides a ROS 2 control interface for manipulating a UR5 robotic arm, including:
- Sinusoidal joint motion for dynamic demonstrations
- Joint-space trajectory control between predefined configurations
- Cartesian-space trajectory planning using KDL kinematics
.
├── ros2_nr_motion_control # Main control package
│ ├── CMakeLists.txt
│ ├── package.xml
│ ├── LICENSE
│ ├── assets/
│ │ └── NR_Bonus_Task.pdf
│ ├── include/
│ │ └── robot_arm_motion_planner/
│ │ └── robot_arm_motion_planner.hpp
│ ├── src/
│ │ ├── cartesian_space_trajectory_node.cpp
│ │ ├── joint_angle_publisher.cpp
│ │ ├── joint_sine_publisher.cpp
│ │ └── joint_space_trajectory_node.cpp
│ ├── launch/
│ │ ├── cartesian_space_trajectory.launch.py
│ │ ├── joint_space_trajectory.launch.py
│ │ └── sinusoidal_trajectory.launch.py
│ ├── test/
│ │ └── test_robot_arm_motion_planner.cpp
│ └── rviz/
│ └── view_robot.rviz
└── Universal_Robots_ROS2_Gazebo_Simulation # Simulation submodule- Ubuntu 22.04
- ROS 2 Humble
- Classic Gazebo (not Ignition)
- KDL (Kinematics and Dynamics Library)
Clone the repository recursively to include the simulation submodule:
git clone --recurse-submodules [email protected]:robotcopper/ros2_NR_manipulation_challenge.gitThen, build the workspace with colcon:
cd ros2_NR_manipulation_challenge
colcon build --symlink-install
source install/setup.bashGenerates a sinusoidal trajectory across all joints of the UR5 arm:
- Frequency:
0.2 Hz - Amplitude:
-0.5 radians - Offset:
-π / 2
Note
These settings can be changed in
ros2_nr_motion_control
└── src/
└── joint_sine_publisher.cppros2 launch ros2_nr_motion_control sinusoidal_trajectory.launch.pyExecutes a smooth trajectory between two joint configurations:
- Point1:
{3.0, -1.0, 0.0, -1.0, 1.0, 0.0} - Point2:
{3.14, -3.0, 2.0, 1.0, -1.0, 3.0} - Joint Velocity:
1.0 - Joint Acceleration:
1.0
Note
These settings can be changed in
ros2_nr_motion_control
└── src/
└── joint_space_trajectory_node.cppros2 launch ros2_nr_motion_control joint_space_trajectory.launch.pyPlans a trajectory in Cartesian space using inverse kinematics:
- Pose1:
(0.5, 0.5, 0.25, 0.0, π / 3, 0.0)(xyzrpy) - Pose2:
(-0.25, 0.25, 0.75, 0.0, -π / 2, 0.0)(xyzrpy) - Linear Velocity:
0.2 - Linear Acceleration:
0.1
Note
These settings can be changed in
ros2_nr_motion_control
└── src/
└── cartesian_space_trajectory_node.cppros2 launch ros2_nr_motion_control cartesian_space_trajectory.launch.pyImportant
The inverse kinematics solution in the Cartesian motion does not take into account the case where the trajectory goes outside the robot's workspace. Ensure that the movement points are consistent with the robot's workspace.
Note
The display of motion in joint space and motion in Cartesian space is looped (the beginning becomes the end when a trajectory is executed) for better visualization of motion between the two points only.
Unit tests are available for the core trajectory planning library robot_arm_motion_planner. To run the tests:
colcon test --packages-select ros2_nr_motion_control --event-handlers console_direct+This will execute the test suite located in:
ros2_nr_motion_control
└── test/
└── test_robot_arm_motion_planner.cppMake sure the workspace has been built beforehand. The output will be displayed directly in the console.
This project is licensed under the BSD 3-Clause License.


