rotorcraft component
- Ports
- Services
- get_sensor_rate (attribute)
- set_sensor_rate (function)
- get_battery (attribute)
- set_battery_limits (attribute)
- get_calibration_param (attribute)
- set_calibration_param (attribute)
- get_imu_calibration (attribute)
- set_imu_calibration (function)
- get_imu_filter (function)
- set_imu_filter (function)
- get_imu_temp (attribute)
- set_timeout (attribute)
- set_ramp (attribute)
- get_cmd_filter (function)
- set_cmd_filter (function)
- connect (activity)
- pconnect (activity)
- disconnect (activity)
- monitor (activity)
- disable_motor (function)
- enable_motor (function)
- set_pid (function)
- calibrate_imu (activity)
- calibrate_mag (activity)
- set_zero (activity)
- set_zero_velocity (activity)
- start (activity)
- servo (activity)
- set_velocity (function)
- set_throttle (function)
- stop (activity)
- log (activity)
- log_stop (function)
- log_info (function)
- get_sensor_average (activity)
- Tasks
Control multi-rotor UAVs using the telekyb3 protocol.
Ports
rotor_input (in)
Data structure
|
rotor_measure (out)
Data structure
|
imu (out)
Data structure
|
Provides current gyroscopes and accelerometer measurements.
According to the nature of data, the port is filled with the imu
data timestamp ts
, intrinsic
true, no position (pos
and
pos_cov
are absent) and linear velocities vx
, vy
, vz
set to
NaN
. All other elements are always present.
mag (out)
Data structure
|
Provides current magnetometer measurements.
Services
get_sensor_rate (attribute)
Outputs
|
Get hardware sensor data publishing rate, see set_sensor_rate (function).
set_sensor_rate (function)
Inputs
|
Set hardware sensor data publishing rate, in Hz
imu
and mag
control the update frequency of port imu (out) and
mag (out) respectively, while motor
and battery
indirectly control
the port rotor_measure (out).
The hardware may not be able to achieve the desired
frequency, especially for motor data when many motors are
controlled. In this case, no error will be reported, but the ports
update rate may be lower than expected and the servo (activity) service
will smoothly stop the motors.
|
get_battery (attribute)
Outputs
|
Get current battery voltage and limits.
set_battery_limits (attribute)
Inputs
|
Throws
|
Set battery minimum and full voltage
This controls the computed energy left
percentage in the port rotor_measure (out).
get_calibration_param (attribute)
Outputs
|
Get IMU calibration parameters. See set_calibration_param (attribute).
set_calibration_param (attribute)
Inputs
|
Set IMU calibration parameters.
The motion_tolerance
is a multiplicative factor the controls the
sensitivity of the standstill detector used by calibrate_imu (activity).
motion_tolerance
must be greater than 1.0. The closer it is to 1.0,
the more the detector will be sensitive to slight motion, making the
calibration procedure practically cumbersome but hopefully more
precise. A good tradeoff is 10.0, which is the default.
get_imu_calibration (attribute)
Outputs
|
Get current gyroscopes and accelerometer calibration data.
set_imu_calibration (function)
Inputs
|
Set current gyroscopes, accelerometer and magnetometer calibration data.
Calling this service is mandatory after each component start, in order to obtain precise IMU measurements.
Input parameters are typically those returned by a call to get_imu_calibration (attribute) after a successful calibrate_imu (activity) (which see).
get_imu_filter (function)
Outputs
|
set_imu_filter (function)
Inputs
|
set_timeout (attribute)
Inputs
|
Set motor startup timeout
get_cmd_filter (function)
Outputs
|
Get rotor commands low-pass filter.
set_cmd_filter (function)
Inputs
|
Set rotor commands low-pass filter.
connect (activity)
Inputs
|
Throws
|
Context
|
Connect to the hardware.
serial
is the device special file to open, at baud
speed. If one
or more connections are already open, they are all closed first.
See pconnect (activity) to deal with multiple hardware connections.
pconnect (activity)
Inputs
|
Throws
|
Context
|
Connect to multiple hardware devices.
This works like connect (activity), except that existing connections are not closed, so that multiple devices can be connected simultaneously.
serial
is the device special file to open, at baud
speed. If a
connection with the same serial
is already open, it is closed and
replaced by a new one with updated parameters.
imu
, mag
and motor
flags indicates whether the corresponding
part should be used (TRUE
) or ignored (FALSE
).
offset
is a small integer added to the motor ids reported by the
hardware, so that the rotor_measure (out) or rotor_input (in) arrays
present an aggregated view of the different devices. For instance,
to connect two devices that both have 4 motors numbered from 1 to 4,
set the first offset to 0 and the second to 4, so that
rotor_measure (out) (resp. rotor_input (in)) will present (resp. use)
motor ids from 1 to 8 with the first half directed to the first
device and the second half to the second device.
disconnect (activity)
Throws
|
Context
|
Disconnect from the hardware
monitor (activity)
Throws
|
Context
|
Monitor connection status
disable_motor (function)
Inputs
|
Disable checking a motor status when it is disconnected
enable_motor (function)
Inputs
|
Disable checking a motor status when it is disconnected
set_pid (function)
Inputs
|
Throws
|
Update the hardware PID controller parameters, on hardware that implements this.
calibrate_imu (activity)
Inputs
|
Throws
|
Context
|
Calibrate accelerometers, gyroscopes and magnetometer.
This service computes the 3×3
scaling matrices and 3D
bias vector
for gyroscopes, accelerometers and magnetometers so that all data is
returned in a consistent, orthogonal frame of reference. This is done
by implementing the paper ‘A robust and easy to implement method for
IMU calibration without external equipments, ICRA 2014’. It requires
no external sensor and a minimum of 10 static poses spanning the
whole SO(3) space, with moderate motion in between. The standard
deviation of the sensor noise is also estimated.
The tstill
parameter controls the time after which a standstill
position is detected (2 seconds is fine), while nposes
sets the
required number of such standstill positions (minimum 10). The
duration of motion between two standstill positions must not exceed
thirty times the tstill
parameter (60 seconds by default).
While running the calibration, a progress indication will be reported
to the standard output of the component. You should first set the
platform in the first standstill orientation, then start the service.
The service will report stay still
until it has acquired the
first pose, then report acquired pose 1
. You can then move to the
next standstill orientation, leave it until you read the same
messages again, and so on for all the nposes
orientations.
For the calibration to be precise, all the orientations have to be as different as possible one from each other. Also, when moving from one orientation to another, try to perform a motion such that the angular velocities on all 3 axis are not zero.
If you don’t read stay still
after moving to a new
pose, this means that the platform may be vibrating or slightly
moving, and the standstill detection cannot work. After some time,
the service will eventually abort and also report it on the standard
output.
Once all orientations have been acquired, the results are set for the current running instance, and available with get_imu_calibration (attribute). Make sure to save the results somewhere before stopping the component, so that you can load them with set_imu_calibration (function) when you later restart.
If a log file name has been specified in path
, the file is filled
with all samples acquired during calibration, corrected with the
newly estimated calibration parameters. In addition, a boolean
indicates for each sample if it is considered as part of a standstill
position or not, so that the quality of the calibration can be
visually assessed.
This procedure does not set any particular vertical axis and the IMU will typically end up calibrated but not aligned with the gravity. Use set_zero (activity) (after calibration) to align the IMU. |
calibrate_mag (activity)
Inputs
|
Throws
|
Context
|
Calibrate magnetometer.
This service computes the 3×3
scaling matrices and 3D
bias vector
for the magnetometers. This is a stripped down version of
calibrate_imu (activity), which see.
Two standstill positions are required, with a motion not exceeding
thirty times the tsill
parameter (2 by default, so 60s of motion).
The motion should cover the full SO(3) space for best results.
set_zero (activity)
Inputs
|
Throws
|
Context
|
Align IMU frame with the gravity vector and reset gyroscopes bias.
This service updates the 3×3
scaling matrices and 3D
bias vector
for both gyroscopes and accelerometers so that the current
accelerometer measurements are only on the Z axis and the gyroscopes
return a 0 angular velocity on each axis.
While running this service, the platform should be perfectly standstill and in a horizontal configuration (i.e. it’s roll and pitch angles are considered zero).
After completion, the current calibration results are updated and can be retrieved with get_imu_calibration (attribute).
This service should be called quite often, as the gyroscopes bias are much dependent on the temperature, so it is important to estimate them well.
set_zero_velocity (activity)
Inputs
|
Throws
|
Context
|
Reset gyroscopes bias.
This service updates the 3D
bias vector for gyroscopes so that the
the gyroscopes return a 0 angular velocity on each axis.
While running this service, the platform should be perfectly standstill. This is a subset of what set_zero (activity) does.
After completion, the current calibration results are updated and can be retrieved with get_imu_calibration (attribute).
start (activity)
Throws
|
Context
|
Spin propellers at the lowest velocity
servo (activity)
Throws
|
Context
|
Control the propellers according to the velocities published in rotor_input (in).
The activity will run until it is stopped by stop (activity) or set_velocity (function). It will also stop and raise the e_input exception if there are no published velocities in rotor_input (in) or if they are older than 500ms.
set_velocity (function)
Inputs
|
Throws
|
Context
|
Set the given propeller velocity, once
set_throttle (function)
Inputs
|
Throws
|
Context
|
Set the given propeller voltage
stop (activity)
Context
|
Stop all propellers
log (activity)
Inputs
|
Throws
|
Context
|
Log IMU and commanded wrench
log_info (function)
Outputs
|
Show missed log entries
get_sensor_average (activity)
Inputs
|
Outputs
|
Throws
|
Compute gyroscopes, accelerometers and magnetomers average.
Tasks
main
Context
|