Only released in EOL distros:  

asctec_mav_framework: asctec_hl_comm | asctec_hl_firmware | asctec_hl_gps | asctec_hl_interface

Package Summary

Interfaces to the "HighLevel" Processor of the Ascending Technologies helicopters where fast IMU datafusion with arbitrary external position input and position control is executed at 1 kHz. Furthermore, all relevant data as IMU, GPS and status can be accessed at configurable rates and baudrates.

asctec_mav_framework: asctec_hl_comm | asctec_hl_firmware | asctec_hl_gps | asctec_hl_interface

Package Summary

Interfaces to the "HighLevel" Processor of the Ascending Technologies helicopters where fast IMU datafusion with arbitrary external position input and position control is executed at 1 kHz. Furthermore, all relevant data as IMU, GPS and status can be accessed at configurable rates and baudrates.

asctec_mav_framework: asctec_hl_comm | asctec_hl_firmware | asctec_hl_gps | asctec_hl_interface

Package Summary

Interfaces to the "HighLevel" Processor of the Ascending Technologies helicopters where fast IMU datafusion with arbitrary external position input and position control is executed at 1 kHz. Furthermore, all relevant data as IMU, GPS and status can be accessed at configurable rates and baudrates.

asctec_mav_framework: asctec_hl_comm | asctec_hl_gps | asctec_hl_interface

Package Summary

Interfaces to the "HighLevel" Processor of the Ascending Technologies helicopters where fast IMU datafusion with arbitrary external position input and position control is executed at 1 kHz. Furthermore, all relevant data as IMU, GPS and status can be accessed at configurable rates and baudrates.

Overview

This package provides a ros interface to communicate with the High Level Processor (HLP) of the AscTec AutoPilot. Therefore, firmware for the HLP is needed which is provided in the asctec_hl_firmware package. It does not work with the firmware shipped with the HLP!

Safety Instructions

We put our best effort in making this package working safely. However, usage is completely on your own risk. We disclaim any liability for injuries, damages of the helicopter or to objects. It is your responsibility to ensure a safe operation environment! Always comply with Ascending Technologies' safety guidelines. Additionally:

  • A safety pilot must always be present and he must have the training and ability to fly the UAV manually in any situation.
  • Do not fly over people or close to people. Spectators always stand behind the safety pilot.
  • Always wear proper protection gear (gloves, safety goggles). The safety pilot as well as spectators.
  • In case of any unexpected behavour, the safety pilot should switch both the serial interface switch to "off" and the flight mode switch to "acc" (both switches point away from the pilot then).

  • When having a new or changed setup (new/other controller, different parameters etc), carefully check the expected outputs before flying.

Setup

Serial Connection to the Highlevel Processor

Using a wired connection is recommended, e.g. to the Ascending Technologies AtomBoard. The cable supplied with the AtomBoard can be used. Connect to the serial port 0 of the Highlevel Processor ("HL serial 0") as shown in the AscTec AutoPilot documentation in chapter 4.1. In this case, set ~serial_port to the correct port, and leave ~serial_port_rx and ~serial_port_tx empty.

If you plan to use a wireless serial link, it might be useful to use a dedicated link for each rx and tx for higher bandwidth. In that case, set ~serial_port_rx and ~serial_port_tx accordingly and leave ~serial_port empty.

Baudrate

The baudrate at which the hl_node communicates with the HLP can be set with the ~baudrate parameter. If it doesn't match a supported standard baudrate, the closest standard baudrate is chosen. The HLP tries to detect the baudrate automatically at startup or if there wasn't any communication with the hl_node for longer than ~10 seconds. hl_node sets up its serial port(s) with the desired baudrate and sends a packet ('a') which the HLP uses to detect the correct baudrate. In order for this to work, always switch on the HLP first, then start hl_node. In case you need to restart hl_node with a different baudrate, you have to wait ~10 s until the HLP accepts new baudrate configure packets. Restarting with the same baudrate works immediately. Tested baudrates are: 57600, 115200, 230400, 460800, 921600.

Configurable Packet Rates

Packet rates of certain packets can be configured with the ~packet_rate_* parameters. No polling is done - instead a configuration packet is sent to the HLP which will send the packets in the desired rate accordingly. Note that no checking is done if the packet rates exceed the available bandwidth, so check the correct rate with

rostopic hz <topic> -w <expected rate>

Modes of Operation

In all operation modes, you can enable/disable control output to the LLP by setting the ~/enable_* parameters accordingly. This is helpful, e.g. to debug a controller on a single axis first. Directions and orientations follow the ROS coordinate frame conventions. As with the direct interface to the LLP, it only accepts commands when the serial enable switch is on. In failure, flip off this switch and put the flightmode switch to "acc". There are three modes you can operate the helicopter which you can select with the ~/position_control parameter:

Direct Acceleration Commands

Set ~/position_control to "off". This mode just forwards roll, pitch, yaw (angular velocity) and thrust commands to the LLP. This is similar to directly send commands to the LLP's serial interface. Set the values in asctec_hl_comm/mav_ctrl in rad for roll and pitch, in rad/s for yaw and 0.0 ... 1.0 for thrust and set asctec_hl_comm/mav_ctrl/type to "acceleration". For the scaling to work correctly, you need to set ~/k_stick and ~/k_stick_yaw to the values you can read out from the LLP with the AscTec control software (default 25, 120). Messages have to arrive at least at 10 Hz, otherwise nothing will be forwarded to the LLP. Note: yaw rates are limited to +- 85% so that the motors cannot be switched on/off accidentally in case of bad commands (motors idle, full yaw).

GPS Based Velocity Control

Set ~/position_control to "GPS" and set asctec_hl_comm/mav_ctrl/type to "velocity" in your messages. Commands are also forwarded to the LLP, but the GPS bit is set additionally. The values in asctec_hl_comm/mav_ctrl correnspond to velocities in boady coordinates in m/s and rad/s respectively. For the scaling to work correctly, you need to set ~/max_velocity_* according to the maximum "stick-GPS" velocites which you can read out from the LLP with the AscTec control software. Defaults are 5 m/s for x/y, and 2 m/s for z. Messages have to arrive at least at 10 Hz, otherwise nothing will be forwarded to the LLP. Note: yaw rates are limited to +- 85% so that the motors cannot be switched on/off accidentally in case of bad commands (full descend rate, full yaw)

Sending GPS waypoints over the HLP to the LLP is currently not implemented as it is not available on the interface between HLP and LLP.

Position Control on the HLP

This is the most interesting part and main motivation for this project. It is designed for position control based on position measurements from e.g. onboard visual SLAM with typically slow update rates. To deal with those delays, datafusion with IMU and position control is performed on the HLP at a rate of 1 kHz. Details on how the controller and datafusion work can be found in Onboard IMU and Monocular Vision Based Control for MAVs in Unknown In- and Outdoor Environments. To work with this mode, please go carefully through this tutorial.

Nodes

hl_interface

interface to the high level processor (HLP) of the AscTec AutoPilot

Subscribed Topics

fcu/control (asctec_hl_comm/mav_ctrl)
  • listens to control commands on this topic
fcu/pose (geometry_msgs/PoseWithCovarianceStamped)
  • listens on this topic for pose updates
fcu/state (asctec_hl_comm/mav_state)
  • listens on this topic for state updates. This bypasses the state estimation on the HLP
fcu/ekf_state_in (sensor_fusion_comm/ExtEkf)

Published Topics

fcu/imu_custom (asctec_hl_comm/mav_imu)
  • custom imu package without covariance, with height and differential height
fcu/imu (sensor_msgs/Imu)
  • Imu sensor data
fcu/gps (sensor_msgs/NavSatFix)
fcu/rcdata (asctec_hl_comm/mav_rcdata)
  • values of the RC channels receiver by the AutoPilot
fcu/status (asctec_hl_comm/mav_status)
  • status of the helicopter
fcu/debug (asctec_hl_comm/DoubleArrayStamped)
  • debug values from the SSDK
fcu/current_pose (geometry_msgs/PoseStamped)
  • publishes the pose that is currently used for position control on the HLP
fcu/ekf_state_out (sensor_fusion_comm/ExtEkf)

Services

fcu/motor_control (asctec_hl_comm/mav_ctrl_motors)
  • service to switch the motors on/off. Use this carefully, it also works during flight!.

Parameters

Static parameters
parameters that are statically set
~serial_port_rx (string, default: )
  • serial port for rx
~serial_port_tx (string, default: )
  • serial port for tx
~serial_port (string, default: /dev/ttyUSB0)
  • serial port used for rx and tx
~baudrate (int, default: 57600)
  • baudrate for the serial port(s)
~frame_id (string, default: fcu)
  • frame id
~k_stick (int, default: 25)
  • gain from AutoPilot values to 1/1000 degree for the input from the pitch and roll "stick"
~k_stick_yaw (int, default: 120)
  • gain from AutoPilot values to 1/1000 degree for the input from the yaw "stick"
~stddev_angular_velocity (double, default: 0.013)
  • standard deviation for angular velocity, default from experiments
~stddev_linear_acceleration (double, default: 0.083)
  • standard deviation for linear acceleration, default from experiments
Dynamically Reconfigurable Parameters Part I (fcu)
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~packet_rate_imu (double, default: 50.0)
  • configures packet rate [Hz] of imu packet. Range: 0.0 to 1000.0
~packet_rate_rc (double, default: 10.0)
  • configures packet rate [Hz] of rc packet. Range: 0.0 to 1000.0
~packet_rate_gps (double, default: 5.0)
  • configures packet rate [Hz] of gps packet. Range: 0.0 to 1000.0
~packet_rate_ssdk_debug (double, default: 5.0)
  • configures packet rate [Hz] of ssdk debug packet. Range: 0.0 to 1000.0
~packet_rate_ekf_state (double, default: 0.0)
  • configures packet rate [Hz] of ekf state packet. Range: 0.0 to 1000.0
~enable_x (bool, default: True)
  • enables x-control.
~enable_y (bool, default: True)
  • enables y-control.
~enable_z (bool, default: True)
  • enables z-control.
~enable_yaw (bool, default: True)
  • enables yaw-control.
~position_control (str, default: off)
  • Enables position control either on the HLP or GPS based position control on the LLP. Possible values are: POSCTRL_OFF (off): position control off, POSCTRL_HIGHLEVEL (HighLevel): position control runs on the HLP., POSCTRL_GPS (GPS): gps position control on the LLP.
~state_estimation (str, default: off)
  • Determines where state estimation is performed. Possible values are: STATE_EST_OFF (off): state estimation off, STATE_EST_HIGHLEVEL_SSDK (HighLevel_SSDK): state estimation runs on the HLP within the SSDK., STATE_EST_HIGHLEVEL_EKF (HighLevel_EKF): state estimation runs on the HLP within an EKF., STATE_EST_EXTERN (Extern): state estimation is performed externally.
~max_velocity_xy (double, default: 0.5)
  • maximum velocity in x/y [m/s]. Range: 0.0 to 10.0
~max_velocity_z (double, default: 0.5)
  • maximum velocity in z [m/s]. Range: 0.0 to 2.0
~max_velocity_yaw (double, default: 0.1)
  • maximum velocity yaw [rad/s]. Range: 0.0 to 1.57
~min_pos_x (double, default: -1000.0)
  • lower bound for position x [m]. Range: -1000.0 to 1000.0
~min_pos_y (double, default: -1000.0)
  • lower bound for position y [m]. Range: -1000.0 to 1000.0
~min_pos_z (double, default: -1000.0)
  • lower bound for position z [m]. Range: -1000.0 to 1000.0
~max_pos_x (double, default: 1000.0)
  • upper bound for position x [m]. Range: -1000.0 to 1000.0
~max_pos_y (double, default: 1000.0)
  • upper bound for position y [m]. Range: -1000.0 to 1000.0
~max_pos_z (double, default: 1000.0)
  • upper bound for position z [m]. Range: -1000.0 to 1000.0
Dynamically Reconfigurable Parameters Part II (fcu/ssdk)
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~ssdk/listen_on_tf (bool, default: True)
  • Enables listening on tf transforms for position updates for the state estimation on the HLP.
~ssdk/tf_ref_frame_id (str, default: world)
  • tf reference frame.
~ssdk/tf_tracked_frame_id (str, default: pelican)
  • tf frame of the helicopter.
~ssdk/send (bool, default: False)
  • used to send all parameters at once.
~ssdk/omega_0_xy (double, default: 2.5)
  • natural frequency of the position controller's reference model for x and y axis. Range: -100.0 to 100.0
~ssdk/omega_0_z (double, default: 8.0)
  • natural frequency of the position controller's reference model for the z axis. Range: -100.0 to 100.0
~ssdk/zeta_xy (double, default: 1.0)
  • damping of the position controller's reference model for x and y axis. Range: -100.0 to 100.0
~ssdk/zeta_z (double, default: 1.0)
  • damping of the position controller's reference model for the z axis. Range: -100.0 to 100.0
~ssdk/p<channel> (double, default: 0.0)
  • replace <channel> by 1-50. Parameter channels used to configure the SSDK running on the HLP. See detailed description for assignments and values. Range: -100.0 to 100.0

Required tf Transforms

worldmav
  • tf transform from world to helicopter. Used as position update for state estimation on the HLP. Can be changed with ~ssdk/tf_ref_frame_id and ~ssdk/tf_tracked_frame_id.

waypoint_server

provides an action server interface to send the helicopter to waypoints

Action Goal

fcu/waypoint/goal (asctec_hl_comm/WaypointActionGoal)
  • accepts a new waypoint.

Action Result

fcu/waypoint/result (asctec_hl_comm/WaypointActionResult)
  • finally reached waypoint, success/failure.

Action Feedback

fcu/waypoint/feedback (asctec_hl_comm/WaypointActionFeedback)
  • current position of the helicopter and distance to waypoint.

Subscribed Topics

fcu/current_pose (asctec_hl_comm/mav_ctrl)
  • listens to the pose that the helicopter's position controller is currently using. Needed to determine if a waypoint is reached and for feedback messages.

waypoint_client

sample waypoint client to send waypoints from the command line

Action Goal

fcu/waypoint/goal (asctec_hl_comm/WaypointActionGoal)
  • sends a new waypoint.

Action Result

fcu/waypoint/result (asctec_hl_comm/WaypointActionResult)
  • listens to finally reached waypoint, success/failure.

Action Feedback

fcu/waypoint/feedback (asctec_hl_comm/WaypointActionFeedback)
  • listens to current position of the helicopter and distance to waypoint.

Scripts

All plot_* scripts plot IMU data from the LLP and debug data from the SSDK running on the HLP. For the SSDK, data is displayed in the North East Down (NED) convention, i.e. data is rotated 180° around the x-axis. y(NED) = -y(ENU), z(NED) = -z(ENU) (height is negative!) and angles likewise according to the right hand rule. Usage:

rosrun asctec_hl_interface plot_position_input [namespace]
#e.g.
rosrun asctec_hl_interface plot_position_input pelican

plot_acceleration

plots acceleration sensor values in body coordinates in m/s^2.

plot_angular_velocity

plots angular velocity in body coordinates in rad/s.

plot_orientation

plots the orientation quaternion (w, x, y, z).

plot_cmd

plots the commands that were sent to the HLP.

plot_ctrl_output

plots control outputs that are send from the HLP to the LLP. NED convention!

plot_filter_bias

plots the estimated acceleration sensor bias in body coordinates [m/s^2]. NED convention!

plot_filter_velocity

plots the estimated velocity in world coordinates [m/s]. NED convention!

plot_filter_position

plots the estimated position in world coordinates [m]. This should look similar to the results from plot_position_input, but smoother. NED convention!

plot_position_input

plots the position that is sent to the HLP to perform a position update of the filter. NED convention!

Wiki: asctec_hl_interface (last edited 2014-12-09 15:31:33 by AlexandreAlbore)