Only released in EOL distros:  

asctec_drivers: asctec_autopilot | asctec_mon | asctec_msgs | asctec_proc | pelican_urdf

Package Summary

The asctec_proc package is a bridge between the asctec_autopilot software and hardware-independent MAV tools.

asctec_drivers: asctec_autopilot | asctec_mon | asctec_msgs | asctec_proc | ccny_asctec_firmware | ccny_asctec_firmware_2 | pelican_urdf

Package Summary

The asctec_proc package is a bridge between the asctec_autopilot software and hardware-independent MAV tools.

asctec_drivers: asctec_autopilot | asctec_mon | asctec_msgs | asctec_proc | ccny_asctec_firmware | ccny_asctec_firmware_2 | pelican_urdf

Package Summary

The asctec_proc package is a bridge between the asctec_autopilot software and hardware-independent MAV tools.

Details

This package is meant to be used together with asctec_autopilot on an AscTec quadrotor vehicle such as the AscTec Pelican or AscTec Hummingbird. The asctec_proc package provides a two-way translation between the asctec messages published by asctec_autopilot and the hardware-independent MAV messages used by the rest of the system.

The justification for this package is the following: the messages published by and sent to [asctec_autopilot]] are defined by the AscTec Autopilot SDK. They are not in SI units, and are specific to the vehicle hardware. Translating them into conventional ROS messages (such as sensor_msgs/IMU, geometry_msgs/Pose etc) enables the development of generic micro-air vehicle tools that can be shared among various hardware platforms.

Apart from translating messages, the package can (optionally) monitor a state topic and send engage/disengage the vehicle's motors whenever appropriate by sending the "motors on"/"motors off" command to the asctec_autopilot.

Notes

This package does not support all the messages that AscTec provides. If you need to add further functionality, you can contact us about it, or send us the appropriate patch.

Usage

There are two versions of the driver: a standard ROS node, and a ROS nodelet. For performance reasons, we recommend using the nodelet together with the asctec_autopilot nodelet when running them on the onboard computer.

Namespaces

Our convention is to use /asctec/ as the namespace for the messages provided by and sent to asctec_autopilot, and /mav for the hardware-independent MAV messages.

asctec_proc.png

Coordinate frames

At the moment, the package publishes information in the ENU (East-North-Up) frame. While this frame is typically not used for aerial vehicles, it makes for easier integration with the rest of the ROS tools .

Nodes

asctec_proc_node

The asctec_proc_node is a bridge between the asctec_autopilot software and hardware-independent MAV tools.

Subscribed Topics

/asctec/LL_STATUS (asctec_msgs/LL_STATUS) /asctec/IMU_CALCDATA (asctec_msgs/IMU_CALCDATA) /mav/cmd_thrust (std_msgs/Float64)
  • A thrust command, in the range of 0.0 (no thrust) to 1.0 (max thrust).
/mav/cmd_roll (std_msgs/Float64)
  • A roll command, in the range of -1.0 (maximum roll) to 1.0 (maximum roll). Note the ENU convention.
/mav/cmd_pitch (std_msgs/Float64)
  • A pitch command, in the range of -1.0 (maximum pitch) to 1.0 (maximum pitch). Note the ENU convention.
/mav/cmd_yaw (std_msgs/Float64)
  • A yaw command, in the range of -1.0 (maximum yaw) to 1.0 (maximum yaw). Note the ENU convention.
/mav/state (mav_msgs/State)
  • A state message (OFF, IDLE, FLYING). This topic is only subscribed to if the enable_state_changes flag is set to true. When a transition between OFF and IDLE occurs, the motors are engaged. When a transition between IDLE and OFF occurs, the motors are disengaged.

Published Topics

/mav/imu (sensor_msgs/Imu)
  • Onboard IMU reading
/mav/pressure_height (mav_msgs/Height)
  • The height reported by the onboard pressure sensor (unfiltered)
/mav/pressure_height_filtered (mav_msgs/Height)
  • The height reported by the onboard pressure sensor (filtered)
/asctec/CTRL_INPUT (asctec_msgs/CTRL_INPUT)

Parameters

~enable_state_changes (bool, default: false)
  • whether or not to monitor the mav/state topic and engage/disengage motors.
~enable_ctrl_thrust (bool, default: false)
  • enable thrust control over the serial interface
~enable_ctrl_roll (bool, default: false)
  • enable roll control over the serial interface
~enable_ctrl_pitch (bool, default: false)
  • enable pitch control over the serial interface
~enable_ctrl_yaw (bool, default: false)
  • enable yaw control over the serial interface
~max_ctrl_thrust (int, default: 2200)
  • the maximum thrust ctrl that the autopilot will publish. Note: this is in AscTec units, and is meant to be used as a last line of safety.
~max_ctrl_roll (int, default: 300)
  • the minimum/maximum roll ctrl that the autopilot will publish. Note: this is in AscTec units, and is meant to be used as a last line of safety.
~max_ctrl_pitch (int, default: 300)
  • the minimum/maximum pitch ctrl that the autopilot will publish. Note: this is in AscTec units, and is meant to be used as a last line of safety.
~max_ctrl_yaw (int, default: 600)
  • the minimum/maximum yaw ctrl that the autopilot will publish. Note: this is in AscTec units, and is meant to be used as a last line of safety.

Bug Reports & Feature Requests

We appreciate the time and effort spent submitting bug reports.

Please use our Trac to report bugs or request features.

Wiki: asctec_proc (last edited 2011-06-17 15:34:03 by IvanDryanovski)