Skip to content

Launch the NMPC node

Bárbara Barros Carlos edited this page Aug 20, 2021 · 4 revisions

Preliminaries

  • Use the Crazyflie without the flow deck
  • Start the Crazyflie at position p=(0, 0, 0) w.r.t. the inertial frame
  • Make sure that the right-hand coordinate system of the body frame is aligned with the right-hand coordinate system of the inertial frame. In other words, the x you see written on the Crazyflie's frame should always be pointing in the same direction as the one in your inertial frame (MOCAP). Experience tells us that, when x was pointing somewhere else, the drone just moves erratically or ends up in an early crash. This stack assumes that both frames are NWU.

Launching the node

To launch the node of the NMPC together with a mocap, use:

$ roslaunch crazyflie_controller acados_predictor.launch

When launched, the NMPC node initially performs a take-off through a regulation. The regulation point is at p=(0, 0, 0.4) and it can be changed in real-time through the GUI of the rqt_reconfigure as shown:

drawing

The Crazyflie will hold the position as long as the flag enable_regulation is True.

To make the quadrotor track a predefined trajectory, you have to click on enable_traj_tracking. This will load one of the trajectories of the folder crazyflie_controller/traj and pass it as reference to the NMPC. There are two trajectories available, we call them: smooth_step and helix_traj. To select the trajectory that will be tracked, you have to edit the launch file:

<node name="nmpc" pkg="crazyflie_controller" type="acados_mpc" output="screen" ns="crazyflie">
	<!--param name="ref_traj" value="$(find crazyflie_controller)/traj/smooth_step.txt"/-->
	<param name="ref_traj" value="$(find crazyflie_controller)/traj/helix_traj.txt"/>
</node>