Overview

These nodes operate together with the controller node. Only one is ACTIVE at any given time but more than one may be in STANDBY which means that it may still publish output messages, though they will not be routed to the vehicle adapter. Modes register themselves with controller at startup but do not go beyond IDLE state unless commanded to do so.

Control Modes

All Modes

Control modes must provide the following (by subclassing flyer_controller::ControlMode):

Subscribed Topics

~cmd (flyer_controller/control_mode_cmd)
  • Commands from controller node
teleop_flyer/joy (joy/Joy)
  • Joystick output as forwarded from teleop_flyer node
odom (nav_msgs/Odometry)
  • State estimate

Published Topics

~output (flyer_controller/control_mode_output)
  • Output of the control mode (commanded pitch and roll angles, etc)
~status (flyer_controller/control_mode_status)
  • Status information

Services Called

controller/control_mode (flyer_controller/control_modes)
  • Used at startup to register mode with controller

Parameters

~status_report_rate (double, default: 5.0)
  • Rate in Hz at which status information is published
~control_output_rate (double, default: 10.0)
  • Rate in Hz at which control output is published

Non-hover Modes

Hover Modes

There are currently two modes based on the idea of linear (PID) control of lateral position based on state estimate, to named hover points.:

The following API is common to these nodes:

Hover Based Modes

Linear (PID) control of lateral position based on state estimate, to named hover points. These topics and params are common to all nodes labeled with (H) below.

Published Topics

~info (flyer_controller/control_mode_hover_info)
  • Information about hover controller useful for debugging (position errors, etc)

Parameters

~min_alt_cmd (double, default: 0.0)
  • [m] commanded altitude corresponding to full - deflection
~max_alt_cmd (double, default: 1.5)
  • [m] commanded altitude corresponding to full + deflection
~KP (double, default: 12.0)
  • Controller proportional gain, in deg/m
~KI (double, default: 1.0)
  • Controller integral gain, in deg per m-s
~KD (double, default: 8.0)
  • Controller derivative gain, in deg/m/s
~Ilimit (double, default: 2.0)
  • Controller integral term limit, in deg

TODO: Describe API for defining named hover points.

Wiki: flyer_controller/control_modes (last edited 2011-07-14 15:20:08 by PatrickBouffard)