-
Notifications
You must be signed in to change notification settings - Fork 11
ROS control
As a prerequisite for the following tasks, install the following ROS packages:
sudo apt install -y \
ros-<distro>-moveit \
ros-<distro>-panda-moveit-config \
ros-<distro>-franka-ros \
ros-<distro>-plotjuggler-ros
So far, we only used rviz
to visualize information from the ROS eco system, e.g. the robot state or planned trajectories.
To actually test real robot-environment interaction, we need to use a physics engine. The default physics engine in ROS is Gazebo
.
Start the Panda robot in Gazebo as follows: roslaunch franka_gazebo panda.launch
Use rosrun plotjuggler plotjuggler
to track the joint state of the first joint.
To this end, start streaming from the ROS Topic Subscriber
plugin, which opens a dialog to select topics. Choose /joint_states
.
Next, in the Timeseries List
choose joint_states -> panda_joint1 -> position
and drag the line into the plot window.
Familiarize with the GUI following the first PlotJuggler tutorial.
Gazebo uses ROS Control to actuate joints. To this end, a controller_manager
is running as part of the Gazebo simulation loop.
One can load and activate various controllers to the manager. rqt
provides a GUI interface to interact with the controller_manager
.
Start rqt
and open Plugins -> Robot Tools -> Controller Manager
Select the /controller_manager
namespace to list all available controllers know to this manager.
You can now load, start, and stop individual controllers. To this end use the right mouse button.
Load and start the effort_joint_trajectory_controller
. Next try to load and start the position_joint_trajectory_controller
. This should fail.
Explain the corresponding error message in the console you started Gazebo from.
In rqt
open another plugin: Plugins -> Robot Tools -> Joint trajectory controller
.
Again select the correct namespace and the previously started effort_joint_trajectory_controller
.
Enable the control sliders by clicking the switch button. You should now be able to operate individual joints via the sliders.
Bring joint1
to 90°.
In rqt
also open the plugin: Plugins -> Configuration -> Dynamic Regconfigure
. Note that you can rearrange plugin windows via dragging.
Dynamic Regconfigure
allows to interactively modify specific ROS parameters - namely those that are prepared for dynamic reconfiguration.
Localize the PID gains of the effort_joint_trajectory_controller
. In the following we will only adapt gains for panda_joint1
.
The following tasks refer to slide Force/Torque based PD control
of the lecture.
What kind of behavior do you expect for the controller when adapting the gains as follows. Always verify your expectation by observing the unit-step response curve with PlotJuggler!
- Set all PID gains to zero.
- Choose a low P-gain of 1 (all others stay zero).
- Choose a larger P-gain of 100. You should observe damping. Where does it come from?
- Estimate the moving mass
$m$ from the natural frequency$w_n = \sqrt{k_p / m}$ .
Note that you can pause theROS Topic Subscriber
in PlotJuggler.
Do you yield similar mass values for a P-gain of 1 and 100? - Compute (and validate) criticial damping parameters for P-gain values of 1, 10, and 100.
Do you still observe oscillation? How much can you reduce the D-gain w/o inducing visible oscillations? Estimate b from the difference. - Validate your PD gains again, but now with the arm fully extended horizontally.
Explain the different behavior!
Now consider panda_joint2
. Keep the robot fully extended.
- Find critical damping parameters for P=1
- What's the steady-state error for a target value of
$q_2 = 1$ ?
Where does it come from? Why didn't we observe a steady-state error for joint 1? - Try to introduce an I-gain to reduce the steady-state error.