Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found
Select Git revision

Target

Select target project
  • kit/aifb/BIS/kit-bis/robotik/ros-learning-platform/learn-environment-franka-emika-panda
1 result
Select Git revision
Show changes
Commits on Source (1)
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## Controller_Task
### Activate_Controller
## Controller Task
### Activate Controller
> In this task, you will learn ...
>
> - how to activate a controller
> - how to check if a controller is already loaded
> - how to load a controller if it is not already loaded
> - how to create a service proxy for loading a controller
> - how to handle service responses and ensure the controller is successfully loaded
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
from controller_manager_msgs.srv import LoadController, SwitchController, SwitchControllerRequest, ListControllers
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
### Task :
Now we want to activate the position controller.
#### Procedure:
- First, use the `wait_for_service` method to wait for the `/controller_manager/list_controllers` service.
- Then create a service proxy for this service and retrieve the list of loaded controllers.
- Check if the `position_joint_trajectory_controller` is already loaded.
- If not, use the `wait_for_service` method to wait for the `/controller_manager/load_controller` service.
- Then create a service proxy for this service and load the controller.
- Now use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.
- Then create a service proxy for this service.
- Create a new request (`SwitchControllerRequest`) and add the `position_joint_trajectory_controller` to the `start_controllers` list.
- Set the `strictness` to `BEST_EFFORT`.
- Check if the service was successful.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
# Define the controllers
controller_to_activate = 'position_joint_trajectory_controller'
# Check if the controller is already loaded
rospy.wait_for_service('/controller_manager/list_controllers')
list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)
loaded_controllers = [controller.name for controller in list_controllers().controller]
if controller_to_activate not in loaded_controllers:
# Service for loading the controller to be activated
rospy.wait_for_service('/controller_manager/load_controller')
load_service = rospy.ServiceProxy('/controller_manager/load_controller', LoadController)
response = load_service(controller_to_activate)
assert response.ok, "Controller could not be loaded."
# Service for switching to the controller to be activated
rospy.wait_for_service('/controller_manager/switch_controller')
switch_service = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)
switch_req = SwitchControllerRequest()
switch_req.start_controllers = [controller_to_activate]
switch_req.strictness = SwitchControllerRequest.BEST_EFFORT
response = switch_service(switch_req)
assert response.ok, "Controller could not be started."
# Add a short sleep to ensure the controller is fully activated
rospy.sleep(3)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
### Summary
In this task, you learned how to activate a controller and use ROS services to interact with the controller manager.
### Next Steps
In the next notebook, we will use the trajectory to control the robot. This will help you gain a deeper understanding of controlling robots in ROS.
Proceed with `use_position_controller` to learn how to use a controller.
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## Controller_Task
### Position_Controller
## Controller Task
### Position Controller
> In this task, you will learn ...
>
> - how to use the position controller to send joint trajectory commands
> - how to create and publish JointTrajectory messages
> - how to define target positions and durations for joint movements
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import sys
import math
import rospy
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from moveit_commander import roscpp_shutdown, roscpp_initialize
from controller_manager_msgs.srv import SwitchController, SwitchControllerRequest
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Now the ROS node is initialized, a publisher is created for the command topic and waited until the publisher is created.
The publisher sends messages of the type JointTrajectory to the topic /position_joint_trajectory_controller/command. The parameter queue_size=10 sets the size of the message queue. This means that up to 10 messages are held in the queue before old messages are discarded.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Initialize the ROS communication infrastructure
roscpp_initialize(sys.argv)
# Initialize ROS
rospy.init_node('position_control', anonymous=True)
# Publisher for the command topic
pub = rospy.Publisher('/position_joint_trajectory_controller/command', JointTrajectory, queue_size=10)
# Wait until the publisher is ready
rospy.sleep(2)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
The position controller receives messages of the type trajectory_msgs/JointTrajectory.
This message contains joint_names, a list of the joints to be controlled, and points, a list of positions to control the joints.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# create a JointTrajectory message
traj_msg = JointTrajectory()
traj_msg.joint_names = ['panda_joint1', 'panda_joint2', 'panda_joint3', 'panda_joint4', 'panda_joint5', 'panda_joint6', 'panda_joint7']
# create a JointTrajectoryPoin
point = JointTrajectoryPoint()
# Here the target positions (in radians) for each joint are added as a list
point.positions = [0.5, -0.5, 0.0, 0.0, 0.5, -0.5, 0.0]
# Now the time is set until the movement should be completed
point.time_from_start = rospy.Duration(2.0)
# Finally, the point is added to the trajectory
traj_msg.points.append(point)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
### Task :
Now you have to define one more target position yourself.
#### Procedure:
##### Add target positions:
Create a JointTrajectoryPoint to define the target positions for each joint and complete the following fields:
- positions: The target positions in Radiant (e.g. [0.5, -0.5, 0.0])
- time_from_start: The time it takes for the robot to reach the positions
The joints should take the following values:
- Joint1 : π / 2
- Joint2 : - π / 4
- Joint3 : 0.0
- Joint4 : - 3 * π / 4
- Joint5 : 0.0
- Joint6 : π / 2
- Joint7 : π / 4
Now add the point to the trajectory.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
# define the target position
point1 = JointTrajectoryPoint()
point1.positions = [math.pi / 2, -math.pi / 4, 0.0, -math.pi * 3 / 4, 0.0, math.pi / 2, math.pi / 4]
point1.time_from_start = rospy.Duration(4.0)
traj_msg.points.append(point1)
rospy.sleep(2)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
Now a message is sent via a publisher and it is ensured that the message is processed by waiting briefly.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# send the message
pub.publish(traj_msg)
# Ensure the message is processed
rospy.sleep(6)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
Now switch back to the previously active controllers, which are the franke_gripper_controller, the franka_state_controller and the effort_joint_trajectory_controller.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# switch back to the previous controllers
rospy.wait_for_service('/controller_manager/switch_controller')
try:
switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)
req = SwitchControllerRequest()
req.stop_controllers = ['position_joint_trajectory_controller']
# restart the previously active controllers
req.start_controllers = ['franka_gripper', 'franka_state_controller', 'effort_joint_trajectory_controller']
req.strictness = SwitchControllerRequest.BEST_EFFORT
response = switch_controller(req)
assert response.ok, "Previous controllers could not be restarted."
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s" % e)
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
### Cleaning up and quitting the ROS node
At the end, the ROS node is shut down and the resources are released.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
# Shutdown the ROS node
rospy.signal_shutdown("Task completed")
roscpp_shutdown()
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
### Summary
In these three notebooks (stop_controller, activate_controller and use_position_controller), you have learned how to:
1. Use the position controller to send joint trajectories and define target positions for joint movements.
2. Stop all active controllers to avoid conflicts and how to use the controller manager and ROS services to interact with the controller manager.
3. Activate a controller and ensure that it is successfully loaded and started.
......
%% Cell type:markdown id: tags:
# Educational Plattform Panda Robot
Author: uninh, uqwfa, ultck
%% Cell type:markdown id: tags:
## Controller_Task
### Stop_Controller
## Controller Task
### Stop Controller
> In this task, you will learn ...
>
> - how to stop all active controllers to ensure no conflicts occur.
> - how to work with the controller manager.
> - how to use ROS services to interact with the controller manager.
> - how to handle service proxies and requests in ROS.
> - how to filter and manage controller states.
%% Cell type:code id: tags:
```
##### DO NOT CHANGE #####
import rospy
from controller_manager_msgs.srv import SwitchController, SwitchControllerRequest, ListControllers
##### DO NOT CHANGE #####
```
%% Cell type:markdown id: tags:
### Task :
First off all we want to stop all active controllers.
#### Procedure:
- Use the 'wait_for_service' method to wait for the `/controller_manager/list_controllers`
- Then create a service proxy for this service and retrieve the list of active controllers.
- Filter the controllers that have the state 'running' and save their names in a list.
- Use the `wait_for_service` method to wait for the `/controller_manager/switch_controller` service.
- Then create a service proxy for this service.
- Create a new request (`SwitchControllerRequest`) and add the list of active controllers to the `stop_controllers` list.
- Set the `strictness` to `BEST_EFFORT`.
- Check if the service was successful.
%% Cell type:code id: tags:
```
##### YOUR CODE HERE #####
rospy.wait_for_service('/controller_manager/list_controllers')
list_controllers = rospy.ServiceProxy('/controller_manager/list_controllers', ListControllers)
# Retrieve the list of active controllers and filter those that are running
active_controllers = [controller.name for controller in list_controllers().controller if controller.state == 'running']
if active_controllers:
# Wait for the switch_controller service to become available
rospy.wait_for_service('/controller_manager/switch_controller')
try:
switch_controller = rospy.ServiceProxy('/controller_manager/switch_controller', SwitchController)
# Create a request to stop the active controllers
req = SwitchControllerRequest()
req.stop_controllers = active_controllers
req.strictness = SwitchControllerRequest.BEST_EFFORT
# Call the service and check if the request was successful
response = switch_controller(req)
assert response.ok, "Active controllers could not be stopped."
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s" % e)
##### YOUR CODE HERE #####
```
%% Cell type:markdown id: tags:
### Summary
In this task, you have learned how to stop all active controllers and use ROS services to interact with the controller manager.
### Next Steps
In the next notebook, we will focus on how to activate a controller. This will help you develop a deeper understanding of managing controllers in ROS.
Proceed to `Activate_Controller` to learn how to activate a controller.
......
......@@ -135,20 +135,20 @@
{
"title": "Task 1",
"description": "Understand how to stop the currently running controllers",
"solution_file": "/stop_controller.ipynb",
"evaluation_file": "/stop_controller_eval.py"
"solution_file": "/controller_task_1.ipynb",
"evaluation_file": "/controller_task_1_eval.py"
},
{
"title": "Task 2",
"description": "Understand how to activate a controller",
"solution_file": "/activate_controller.ipynb",
"evaluation_file": "/activate_controller_eval.py"
"solution_file": "/controller_task_2.ipynb",
"evaluation_file": "/controller_task_2_eval.py"
},
{
"title": "Task 3",
"description": "Understand the basics of the position controller",
"solution_file": "/position_controller.ipynb",
"evaluation_file": "/position_controller_eval.py"
"solution_file": "/controller_task_3.ipynb",
"evaluation_file": "/controller_task_3_eval.py"
}
]
}
......