Skip to content
Snippets Groups Projects
Commit 9c6c8647 authored by Max Maria Humbert's avatar Max Maria Humbert
Browse files

change movement algorithm in move it basics 1

parent 1ce9f388
No related branches found
No related tags found
No related merge requests found
......@@ -9,7 +9,7 @@ roscpp_initialize(sys.argv)
rospy.init_node('move_it_basics_1_eval', anonymous=True)
group = MoveGroupCommander("panda_arm")
group.set_planner_id("RRTConnectkConfigDefault")
group.set_planner_id("RRTConnect")
group.set_num_planning_attempts(10)
current_joint_values = group.get_current_joint_values()
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## MoveIt Basics
### Task 1
---
> In this task, you will learn ...
>
> - ... what MoveIt is.
> - ... how to use it.
---
%% Cell type:markdown id: tags:
After mastering the direct method of rotating the Panda robot’s joints using ``ROS``, it’s time to explore an easier approach. For this, we’ll use the ``MoveIt`` package. The ``MoveIt Commander`` Python package provides a straightforward interface for motion planning and Cartesian path computation. MoveIt, as a whole, is a robust framework for motion planning and robot manipulation.
%% Cell type:markdown id: tags:
First, we need to import the required modules. We still use ``rospy`` to initialize a``ROS node``. What’s new here are ``MoveGroupCommander``, ``roscpp_initialize``, and ``roscpp_shutdown`` from the ``MoveIt Commander`` package. As the names suggest, ``roscpp_initialize`` is used to initialize, and ``roscpp_shutdown`` to shut down the ``MoveIt Commander`` within the ``ROS system``. The ``MoveGroupCommander``, on the other hand, acts as the core interface for commanding robot motion planning.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
import math
import sys
from moveit_commander import MoveGroupCommander, roscpp_initialize, roscpp_shutdown
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
The next step would be initialize roscpp and initialize a ``ROS node``.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
roscpp_initialize(sys.argv)
rospy.init_node('commander', anonymous=True)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Next, we create a ``MoveGroupCommander`` instance. We configure it to use the planning algorithm ``'RRTConnectkConfigDefault'`` and set the number of planning attempts to 10 for better motion planning results.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
group = MoveGroupCommander("panda_arm")
group.set_planner_id("RRTConnectkConfigDefault")
group.set_planner_id("RRTConnect")
group.set_num_planning_attempts(10)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Now we can adjust the joint values. To do this, use the ``get_current_joint_values()`` method of the ``MoveGroupCommander`` to retrieve the current joint values, then modify the specific axes you want.
ToDo:
- add 50 degrees to the joint4 and store the changed values in the ``joint_goal`` variable
%% Cell type:code id: tags:
```
joint_goal = None
##### YOUR CODE HERE #####
joint_goal = group.get_current_joint_values()
joint_goal[4] += (50 * math.pi) / 180
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
We can now set our ``joint_goal`` as the target joint values for the ``MoveGroupCommander`` by using the ``set_joint_value_target()`` method. Once the target is set, execute the movement with the ``go(wait=True)`` method.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
group.set_joint_value_target(joint_goal)
group.go(wait=True)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
As always, we clean up by deleting the node and shutting down the MoveIt Commander.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
rospy.signal_shutdown("Task completed")
roscpp_shutdown()
##### DO NOT CHANGE #####
```
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment